|
| struct | ALFunction |
| | Primal-dual augmented Lagrangian merit function. More...
|
| |
| struct | AngularAccelerationDataTpl |
| |
| struct | AngularAccelerationResidualTpl |
| | This residual returns the angular acceleration of a centroidal model with state \(x = (c, h, L) \), computed from the external forces and contact poses. More...
|
| |
| struct | AngularMomentumDataTpl |
| |
| struct | AngularMomentumResidualTpl |
| | This residual returns the angular momentum for a centroidal model with state \(x = (c, h, L) \). More...
|
| |
| class | ArenaMatrix |
| |
| class | ArmijoLinesearch |
| | Basic backtracking Armijo line-search strategy. More...
|
| |
| class | BlkMatrix |
| | Block matrix class, with a fixed or dynamic-size number of row and column blocks. More...
|
| |
| struct | BoxConstraintTpl |
| | Box constraint set \(z \in [z_\min, z_\max]\). More...
|
| |
| struct | BunchKaufman |
| |
| struct | CallbackBaseTpl |
| | Base callback class. More...
|
| |
| struct | CartesianProductTpl |
| | The cartesian product of two or more manifolds. More...
|
| |
| struct | CenterOfMassTranslationDataTpl |
| |
| struct | CenterOfMassTranslationResidualTpl |
| | This residual returns the Center of Mass translation for a centroidal model with state \(x = (c, h, L) \). More...
|
| |
| struct | CenterOfMassVelocityDataTpl |
| |
| struct | CenterOfMassVelocityResidualTpl |
| |
| struct | CentroidalAccelerationDataTpl |
| |
| struct | CentroidalAccelerationResidualTpl |
| | This residual returns the linear acceleration of a centroidal model with state \(x = (c, h, L) \), computed from the external forces and contact poses. More...
|
| |
| struct | CentroidalCoMDataTpl |
| |
| struct | CentroidalCoMResidualTpl |
| |
| struct | CentroidalFrictionConeDataTpl |
| | This residual implements the "ice cream" friction cone for a centroidal model with state \(x = (c, h, L) \). More...
|
| |
| struct | CentroidalFrictionConeResidualTpl |
| |
| struct | CentroidalMomentumDataTpl |
| |
| struct | CentroidalMomentumDerivativeDataTpl |
| |
| struct | CentroidalMomentumDerivativeResidualTpl |
| | This residual returns the derivative of centroidal momentum for a kinodynamics model. More...
|
| |
| struct | CentroidalMomentumResidualTpl |
| | This residual returns the derivative of centroidal momentum for a kinodynamics model. More...
|
| |
| struct | CentroidalWrapperDataTpl |
| |
| struct | CentroidalWrapperResidualTpl |
| | This residual acts as a wrapper for centroidal model cost functions in which the external forces are added to the state and the control becomes the forces derivatives. More...
|
| |
| struct | CentroidalWrenchConeDataTpl |
| | This residual implements the wrench cone for a centroidal model with control \(u = (f_1,...,f_c) \) with \(f_k\) 6D spatial force. More...
|
| |
| struct | CentroidalWrenchConeResidualTpl |
| |
| struct | CompositeCostDataTpl |
| | Data struct for composite costs. More...
|
| |
| struct | ConstantCostTpl |
| | Constant cost. More...
|
| |
| class | ConstraintProximalScalerTpl |
| |
| struct | ConstraintSetProductTpl |
| | Cartesian product of multiple constraint sets. This class makes computing multipliers and Jacobian matrix projections more convenient. More...
|
| |
| struct | ConstraintSetTpl |
| | Base constraint set type. More...
|
| |
| struct | ConstraintStackTpl |
| | Convenience class to manage a stack of constraints. More...
|
| |
| struct | ContactForceDataTpl |
| |
| struct | ContactForceResidualTpl |
| | This residual returns the derivative of centroidal momentum for a kinodynamics model. More...
|
| |
| struct | ContactMapTpl |
| | Contact map for centroidal costs and dynamics. More...
|
| |
| struct | ControlErrorResidualTpl |
| |
| struct | CostAbstractTpl |
| | Stage costs \( \ell(x, u) \) for control problems. More...
|
| |
| struct | CostDataAbstractTpl |
| | Data struct for CostAbstractTpl. More...
|
| |
| struct | CostStackDataTpl |
| |
| struct | CostStackTpl |
| | Weighted sum of multiple cost components. More...
|
| |
| struct | DCMPositionDataTpl |
| |
| struct | DCMPositionResidualTpl |
| |
| struct | DirectSumCostTpl |
| |
| struct | DirectSumExplicitDynamicsTpl |
| |
| struct | DynamicsDataTpl |
| |
| struct | DynamicsModelTpl |
| | Dynamics model: describes system dynamics through an implicit relation \(f(x,u,x') = 0\). More...
|
| |
| struct | EqualityConstraintTpl |
| | Equality constraints \(c(x) = 0\). More...
|
| |
| struct | ExplicitDynamicsDataTpl |
| | Specific data struct for explicit dynamics ExplicitDynamicsModelTpl. More...
|
| |
| struct | ExplicitDynamicsModelTpl |
| | Explicit forward dynamics model \( x_{k+1} = f(x_k, u_k) \). More...
|
| |
| struct | ExtendedStringHash |
| | Extended hashing function for strings which supports const char* and std::string_view. More...
|
| |
| struct | FilterTpl |
| | A basic filter line-search strategy. More...
|
| |
| struct | FlyHighResidualTpl |
| | A port of sobec's ResidualModelFlyHighTpl. More...
|
| |
| struct | ForwardDynamicsOptions |
| |
| struct | frame_api |
| |
| struct | FrameCollisionDataTpl |
| |
| struct | FrameCollisionResidualTpl |
| |
| struct | FramePlacementDataTpl |
| |
| struct | FramePlacementResidualTpl |
| |
| struct | FrameTranslationDataTpl |
| |
| struct | FrameTranslationResidualTpl |
| |
| struct | FrameVelocityDataTpl |
| |
| struct | FrameVelocityResidualTpl |
| |
| struct | FunctionSliceDataTpl |
| |
| struct | FunctionSliceXprTpl |
| | Represents a function of which the output is a subset of another function, for instance \(x \mapsto f_\{0, 1, 3\}(x) \) where \(f\) is given. More...
|
| |
| struct | FunctionSliceXprTpl< Scalar, StageFunctionTpl< Scalar > > |
| |
| struct | FunctionSliceXprTpl< Scalar, UnaryFunctionTpl< Scalar > > |
| |
| struct | GravityCompensationResidualTpl |
| |
| struct | HistoryCallbackTpl |
| | Store the history of results. More...
|
| |
| struct | is_eigen |
| |
| struct | is_tpl_base_of |
| |
| struct | LagrangianDerivatives |
| | Compute the derivatives of the problem Lagrangian. More...
|
| |
| struct | LinearFunctionCompositionTpl |
| |
| struct | LinearFunctionTpl |
| | Linear function \(f(x,u,y) = Ax + Bu + Cy + d\). More...
|
| |
| struct | LinearMomentumDataTpl |
| |
| struct | LinearMomentumResidualTpl |
| | This residual returns the linear momentum for a centroidal model with state \(x = (c, h, L) \). More...
|
| |
| struct | LinearUnaryFunctionCompositionTpl |
| |
| class | Linesearch |
| | Base linesearch class. Design pattern inspired by Google Ceres-Solver. More...
|
| |
| struct | LinesearchOptions |
| |
| struct | LogColumn |
| |
| struct | Logger |
| | A table logging utility to log the trace of the numerical solvers. More...
|
| |
| struct | LogResidualCostTpl |
| | Log-barrier of an underlying cost function. More...
|
| |
| struct | ManifoldAbstractTpl |
| | Base class for manifolds, to use in cost funcs, solvers... More...
|
| |
| struct | math_types |
| | Typedefs for math (Eigen vectors, matrices) depending on scalar type. More...
|
| |
| class | mimalloc_resource |
| | A memory_resource wrapping around mimalloc. More...
|
| |
| struct | MultibodyConfiguration |
| | Multibody configuration group \(\mathcal{Q}\), defined using the Pinocchio library. More...
|
| |
| struct | MultibodyFrictionConeDataTpl |
| |
| struct | MultibodyFrictionConeResidualTpl |
| | This residual returns the derivative of centroidal momentum for a kinodynamics model. More...
|
| |
| struct | MultibodyPhaseSpace |
| | The tangent bundle of a multibody configuration group. More...
|
| |
| struct | MultibodyWrenchConeDataTpl |
| |
| struct | MultibodyWrenchConeResidualTpl |
| | This residual returns the derivative of centroidal momentum for a kinodynamics model. More...
|
| |
| struct | NegativeOrthantTpl |
| | Negative orthant, for constraints \(h(x)\leq 0\). More...
|
| |
| struct | NewtonRaphson |
| | Newton-Raphson procedure, e.g. to compute forward dynamics from implicit functions. More...
|
| |
| struct | NonmonotoneLinesearch |
| | Nonmonotone Linesearch algorithm. Modifies the Armijo condition with a moving average of function values. More...
|
| |
| struct | NonsmoothPenaltyL1Tpl |
| | Composite \(\ell_1\)-penalty function \( \|c(x)\|_1 \). More...
|
| |
| struct | overloads |
| | Utility helper struct for creating visitors from lambdas. More...
|
| |
| struct | PinocchioLieGroup |
| | Wrap a Pinocchio Lie group into a ManifoldAbstractTpl object. More...
|
| |
| class | polymorphic |
| |
| class | polymorphic_allocator |
| | A convenience subclass of std::pmr::polymorphic_allocator for bytes. More...
|
| |
| struct | PolynomialTpl |
| | Polynomials represented by their coefficients in decreasing order of degree. More...
|
| |
| struct | QFunctionTpl |
| | Q-function model parameters. More...
|
| |
| struct | QuadraticControlCostTpl |
| |
| struct | QuadraticCostDataTpl |
| |
| struct | QuadraticCostTpl |
| | Euclidean quadratic cost. More...
|
| |
| struct | QuadraticResidualCostTpl |
| | Quadratic composite of an underlying function. More...
|
| |
| struct | QuadraticStateCostTpl |
| | Quadratic distance cost over the state manifold. More...
|
| |
| struct | RelaxedLogBarrierCostTpl |
| | Log-barrier of an underlying cost function. More...
|
| |
| struct | ResultsBaseTpl |
| |
| struct | ResultsFDDPTpl |
| |
| struct | ResultsTpl |
| | Results holder struct. More...
|
| |
| class | RuntimeError |
| |
| class | shared_ptr |
| | STL class. More...
|
| |
| struct | SolverFDDPTpl |
| | The feasible DDP (FDDP) algorithm, from Mastalli et al. (2020). More...
|
| |
| struct | SolverProxDDPTpl |
| | A proximal, augmented Lagrangian-type solver for trajectory optimization. More...
|
| |
| struct | StageDataTpl |
| | Data struct for stage models StageModelTpl. More...
|
| |
| struct | StageFunctionDataTpl |
| | Base struct for function data. More...
|
| |
| struct | StageFunctionTpl |
| | Class representing ternary functions \(f(x,u,x')\). More...
|
| |
| struct | StageModelTpl |
| | A stage in the control problem. More...
|
| |
| struct | StateErrorResidualTpl |
| | State error \(x \ominus x_\text{ref}\). More...
|
| |
| struct | TangentBundleTpl |
| | Tangent bundle of a base manifold M. More...
|
| |
| struct | TrajOptDataTpl |
| | Problem data struct. More...
|
| |
| struct | TrajOptProblemTpl |
| | Trajectory optimization problem. More...
|
| |
| struct | UnaryFunctionTpl |
| | Represents unary functions of the form \(f(x)\), with no control (or next-state) arguments. More...
|
| |
| struct | ValueFunctionTpl |
| | Storage for the value function model parameters. More...
|
| |
| struct | VectorSpaceTpl |
| | Standard Euclidean vector space. More...
|
| |
| struct | WorkspaceBaseTpl |
| | Base workspace struct for the algorithms. More...
|
| |
| struct | WorkspaceFDDPTpl |
| | Workspace for solver SolverFDDP. More...
|
| |
| struct | WorkspaceTpl |
| | Workspace for solver SolverProxDDP. More...
|
| |
|
| template<typename T> |
| std::ostream & | operator<< (std::ostream &oss, const StageFunctionDataTpl< T > &self) |
| |
| template std::ostream & | operator<< (std::ostream &oss, const StageFunctionDataTpl< context::Scalar > &self) |
| |
| template<typename Scalar> |
| | ArmijoLinesearch (const LinesearchOptions< Scalar > &) -> ArmijoLinesearch< Scalar > |
| |
| template<typename Scalar> |
| | NonmonotoneLinesearch (const LinesearchOptions< Scalar > &) -> NonmonotoneLinesearch< Scalar > |
| |
| template<typename Scalar> |
| std::ostream & | operator<< (std::ostream &oss, const StageModelTpl< Scalar > &sm) |
| |
| template<typename Scalar> |
| Scalar | computeTrajectoryCost (const TrajOptDataTpl< Scalar > &problem_data) |
| | Helper for computing the trajectory cost (from pre-computed problem data).
|
| |
| template<typename T1, typename T2> |
| bool | assign_no_resize (const std::vector< T1 > &lhs, std::vector< T2 > &rhs) |
| | Assign a vector of Eigen types into another, ensure there is no resize.
|
| |
| template<typename Scalar> |
| void | xs_default_init (const TrajOptProblemTpl< Scalar > &problem, std::vector< typename math_types< Scalar >::VectorXs > &xs) |
| | Default-initialize a trajectory to the neutral states for each state space at each stage.
|
| |
| template<typename Scalar> |
| void | us_default_init (const TrajOptProblemTpl< Scalar > &problem, std::vector< typename math_types< Scalar >::VectorXs > &us) |
| | Default-initialize a controls trajectory from the neutral element of each control space.
|
| |
| template<typename Scalar> |
| void | check_initial_guess_and_assign (const TrajOptProblemTpl< Scalar > &problem, const typename math_types< Scalar >::VectorOfVectors &xs_in, const typename math_types< Scalar >::VectorOfVectors &us_in, typename math_types< Scalar >::VectorOfVectors &xs_out, typename math_types< Scalar >::VectorOfVectors &us_out) |
| | Check the input state-control trajectory is a consistent warm-start for the output.
|
| |
| template<typename D> |
| auto | eigenPrintWithPreamble (const Eigen::EigenBase< D > &mat, std::string_view text, Eigen::IOFormat ft=EIGEN_DEFAULT_IO_FORMAT) |
| |
| template<typename Derived> |
| auto | blockMatrixGetRow (const Eigen::MatrixBase< Derived > &matrix, boost::span< const Eigen::Index > rowBlockSizes, std::size_t rowIdx) |
| |
| template<typename Derived> |
| auto | blockVectorGetRow (const Eigen::MatrixBase< Derived > &matrix, boost::span< const Eigen::Index > blockSizes, std::size_t blockIdx) |
| |
| template<typename Scalar> |
| auto | directSum (xyz::polymorphic< CostAbstractTpl< Scalar > > const &c1, xyz::polymorphic< CostAbstractTpl< Scalar > > const &c2) |
| |
| template<typename T> |
| xyz::polymorphic< CostStackTpl< T > > | operator+ (const CostPtr< T > &c1, const CostPtr< T > &c2) |
| |
| template<typename T> |
| xyz::polymorphic< CostStackTpl< T > > | operator+ (xyz::polymorphic< CostStackTpl< T > > &&c1, const CostPtr< T > &c2) |
| |
| template<typename T> |
| xyz::polymorphic< CostStackTpl< T > > | operator+ (xyz::polymorphic< CostStackTpl< T > > &&c1, CostPtr< T > &&c2) |
| |
| template<typename T> |
| xyz::polymorphic< CostStackTpl< T > > | operator+ (const xyz::polymorphic< CostStackTpl< T > > &c1, CostPtr< T > &&c2) |
| |
| template<typename T> |
| xyz::polymorphic< CostStackTpl< T > > | operator* (T u, xyz::polymorphic< CostStackTpl< T > > &&c1) |
| |
| template<typename Scalar> |
| auto | directSum (xyz::polymorphic< ExplicitDynamicsModelTpl< Scalar > > const &m1, xyz::polymorphic< ExplicitDynamicsModelTpl< Scalar > > const &m2) |
| |
| template<typename Scalar> |
| auto | linear_compose (xyz::polymorphic< StageFunctionTpl< Scalar > > func, const typename math_types< Scalar >::ConstMatrixRef A, const typename math_types< Scalar >::ConstVectorRef b) |
| | Create a linear composition of the input function func.
|
| |
| template<typename Scalar> |
| auto | linear_compose (xyz::polymorphic< UnaryFunctionTpl< Scalar > > func, const typename math_types< Scalar >::ConstMatrixRef A, const typename math_types< Scalar >::ConstVectorRef b) |
| | Create a linear composition of the input function func. This will return a UnaryFunctionTpl.
|
| |
| template<typename Scalar, typename ConfigType, typename VelType, typename MatrixType, typename OutType, int Options> |
| void | underactuatedConstrainedInverseDynamics (const ModelTpl< Scalar, Options > &model, DataTpl< Scalar, Options > &data, const Eigen::MatrixBase< ConfigType > &q, Eigen::MatrixBase< VelType > const &v, const Eigen::MatrixBase< MatrixType > &actMatrix, const StdVectorEigenAligned< RigidConstraintModelTpl< Scalar, Options > > &constraint_models, StdVectorEigenAligned< RigidConstraintDataTpl< Scalar, Options > > &constraint_datas, const Eigen::MatrixBase< OutType > &res_) |
| |
| template<typename T> |
| auto | operator* (const xyz::polymorphic< ManifoldAbstractTpl< T > > &left, const xyz::polymorphic< ManifoldAbstractTpl< T > > &right) |
| |
| template<typename T> |
| auto | operator* (const CartesianProductTpl< T > &left, const xyz::polymorphic< ManifoldAbstractTpl< T > > &right) |
| |
| template<typename T> |
| auto | operator* (const xyz::polymorphic< ManifoldAbstractTpl< T > > &left, const CartesianProductTpl< T > &right) |
| |
| template<typename T> |
| auto | operator* (const CartesianProductTpl< T > &left, const CartesianProductTpl< T > &right) |
| |
| template<typename G> |
| | PinocchioLieGroup (const G &) -> PinocchioLieGroup< G > |
| |
| template<class... Ts> |
| | overloads (Ts...) -> overloads< Ts... > |
| |
| template<typename Scalar, typename F, typename M> |
| ALIGATOR_INLINE std::pair< Scalar, Scalar > | fddp_goldstein_linesearch (F &&phi, M &&model, const Scalar phi0, const typename Linesearch< Scalar >::Options &ls_params, Scalar th_grad, Scalar &d1, Scalar th_accept_step=0.1, Scalar th_accept_neg_step=2.0) |
| | The backtracking linesearch from FDDP (Mastalli et al).
|
| |
| template<typename Scalar> |
| Scalar | costDirectionalDerivative (const WorkspaceTpl< Scalar > &workspace, const TrajOptDataTpl< Scalar > &prob_data) |
| | Compute the directional derivative of the cost function.
|
| |
| template<typename Scalar> |
| std::ostream & | operator<< (std::ostream &oss, const ResultsTpl< Scalar > &self) |
| |
| template<typename Scalar> |
| auto | getConstraintProductSet (const ConstraintStackTpl< Scalar > &constraints) |
| |
| template<typename Scalar> |
| std::ostream & | operator<< (std::ostream &oss, const ResultsBaseTpl< Scalar > &self) |
| |
| template<typename T, template< typename > class M, typename D = typename M<T>::Data> |
| void | forwardDynamics (const M< T > &model, const typename math_types< T >::ConstVectorRef &x, const typename math_types< T >::ConstVectorRef &u, D &data, const typename math_types< T >::VectorRef xout, const std::optional< typename math_types< T >::ConstVectorRef > &gap=std::nullopt, ForwardDynamicsOptions< T > opts={}) |
| | Evaluates the forward map for a discrete dynamics model, implicit or explicit.
|
| |
| template<typename T, typename Alloc> |
| void | rotate_vec_left (std::vector< T, Alloc > &v, long n_head=0, long n_tail=0) |
| | Simply rotate an entire std::vector to the left.
|
| |
| template<typename Scalar> |
| math_types< Scalar >::VectorOfVectors | rollout (const std::vector< xyz::polymorphic< DynamicsModelTpl< Scalar > > > &dyn_models, const typename math_types< Scalar >::VectorXs &x0, const typename math_types< Scalar >::VectorOfVectors &us, typename math_types< Scalar >::VectorOfVectors &xout) |
| | Perform a rollout of the supplied dynamical models.
|
| |
| template<typename Scalar> |
| math_types< Scalar >::VectorOfVectors | rollout (const DynamicsModelTpl< Scalar > &dyn_model, const typename math_types< Scalar >::VectorXs &x0, const typename math_types< Scalar >::VectorOfVectors &us) |
| | Perform a rollout of the supplied dynamical models.
|
| |
| template<typename Scalar> |
| void | rollout (const std::vector< xyz::polymorphic< ExplicitDynamicsModelTpl< Scalar > > > &dyn_models, const typename math_types< Scalar >::VectorXs &x0, const typename math_types< Scalar >::VectorOfVectors &us, typename math_types< Scalar >::VectorOfVectors &xout) |
| | Perform a rollout of the supplied dynamical models.
|
| |
| template<typename Scalar> |
| void | rollout (const ExplicitDynamicsModelTpl< Scalar > &dyn_model, const typename math_types< Scalar >::VectorXs &x0, const typename math_types< Scalar >::VectorOfVectors &us, typename math_types< Scalar >::VectorOfVectors &xout) |
| | Perform a rollout of the supplied dynamical models. Rolls out a single ExplicitDynamicsModelTpl.
|
| |
| template<template< typename > class C, typename Scalar> |
| math_types< Scalar >::VectorOfVectors | rollout (const C< Scalar > &dms, const typename math_types< Scalar >::VectorXs &x0, const typename math_types< Scalar >::VectorOfVectors &us) |
| | Perform a rollout of the supplied dynamical models. This variant allocates the output and returns it.
|
| |
| template<template< typename > class C, typename Scalar> |
| math_types< Scalar >::VectorOfVectors | rollout (const std::vector< xyz::polymorphic< C< Scalar > > > &dms, const typename math_types< Scalar >::VectorXs &x0, const typename math_types< Scalar >::VectorOfVectors &us) |
| | Perform a rollout of the supplied dynamical models. This variant allocates the output and returns it.
|
| |
| | _process () |
| |
Main package namespace.
- Copyright
- Copyright (C) 2022-2024 LAAS-CNRS, INRIA
-
Copyright (C) 2024-2025 INRIA
-
Copyright (C) 2023-2024 LAAS-CNRS, 2023-2025 INRIA
- Author
- Wilson Jallet
- Copyright
- Copyright (C) 2025 INRIA
The following overload for get_pointer is defined here, to avoid conflicts with other Boost libraries using get_pointer() without seeing this overload if included later.
- Copyright
- Copyright (C) 2024 LAAS-CNRS, INRIA
- Author
- Wilson Jallet
- Copyright
- Copyright (C) 2025 INRIA
- Author
- Wilson Jallet
- Copyright
- Copyright (C) 2023-2024 LAAS-CNRS, 2023-2025 INRIA
-
Copyright (C) 2023-2024 LAAS-CNRS, 2023-2O25 INRIA
-
Copyright (C) 2024 LAAS-CNRS, 2024-2025 INRIA
- Author
- Wilson Jallet
- Copyright
- Copyright (C) 2022 LAAS-CNRS, INRIA
-
Copyright (C) 2022-2024 LAAS-CNRS, 2022-2025 INRIA
Copyright (C) 2022 LAAS-CNRS, 2022-2025 INRIA
- Copyright
- Copyright (C) 2023 LAAS-CNRS, INRIA
-
Copyright (C) 2022-2023 LAAS-CNRS, 2022-2025 INRIA
-
Copyright (C) 2022 LAAS-CNRS, 2022-2025 INRIA
-
Copyright (C) 2023-2024 LAAS-CNRS, INRIA