aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
aligator Namespace Reference

Main package namespace. More...

Namespaces

namespace  autodiff
 
namespace  compat
 Headers for compatibility modules.
 
namespace  context
 
namespace  detail
 
namespace  dynamics
 Namespace for modelling system dynamics.
 
namespace  gar
 
namespace  math
 Math utilities.
 
namespace  omp
 Utilities to set parallelism options.
 
namespace  python
 The Python bindings.
 
namespace  utils
 

Classes

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  BlkMatrix
 Block matrix class, with a fixed-size number of row and column blocks. More...
 
struct  CallbackBaseTpl
 Base callback class. 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  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  Cloneable
 Mixin which makes a class/class hierarchy cloneable. More...
 
struct  CompositeCostDataTpl
 Data struct for composite costs. More...
 
struct  ConstantCostTpl
 Constant cost. More...
 
class  ConstraintProximalScalerTpl
 Weighting strategy for the constraints in a stack. More...
 
struct  ConstraintStackTpl
 Convenience class to manage a stack of constraints. 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  DefaultScaling
 TODO: NEW G.A.R. BACKEND CAN'T HANDLE DIFFERENT WEIGHTS, PLS FIX. More...
 
struct  DirectSumCostTpl
 
struct  DirectSumExplicitDynamicsTpl
 
struct  DynamicsModelTpl
 Dynamics model: describes system dynamics through an implicit relation \(f(x,u,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  FilterTpl
 A basic filter line-search strategy. More...
 
struct  FlyHighResidualTpl
 A port of sobec's ResidualModelFlyHighTpl. More...
 
struct  forwardDynamics
 Evaluates the forward map for a discrete dynamics model, implicit or explicit. More...
 
struct  frame_api
 
struct  FramePlacementDataTpl
 
struct  FramePlacementResidualTpl
 
struct  FrameTranslationDataTpl
 
struct  FrameTranslationResidualTpl
 
struct  FrameVelocityDataTpl
 
struct  FrameVelocityResidualTpl
 
struct  FrictionConeDataTpl
 This residual implements the "ice cream" friction cone for a centroidal model with state \(x = (c, h, L) \). More...
 
struct  FrictionConeResidualTpl
 
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, UnaryFunctionTpl< Scalar > >
 
struct  HistoryCallbackTpl
 Store the history of results. More...
 
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
 
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  NewtonRaphson
 Newton-Raphson procedure, e.g. to compute forward dynamics from implicit functions. More...
 
struct  PDALFunction
 Primal-dual augmented Lagrangian merit function. More...
 
struct  ProximalDataTpl
 Data for proximal penalty. More...
 
struct  ProximalPenaltyTpl
 Proximal penalty cost. 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  ResultsBaseTpl
 
struct  ResultsFDDPTpl
 
struct  ResultsTpl
 Results holder struct. More...
 
class  RuntimeError
 
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  StageConstraintTpl
 Simple struct holding together a function and set, to describe a constraint. 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
 
struct  TrajectoryTpl
 
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  WorkspaceBaseTpl
 Base workspace struct for the algorithms. More...
 
struct  WorkspaceFDDPTpl
 Workspace for solver SolverFDDP. More...
 
struct  WorkspaceTpl
 Workspace for solver SolverProxDDP. More...
 
struct  WrenchConeDataTpl
 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  WrenchConeResidualTpl
 

Typedefs

template<typename Scalar >
using DynamicsDataTpl = StageFunctionDataTpl<Scalar>
 
template<typename T >
using StdVectorEigenAligned = std::vector<T, Eigen::aligned_allocator<T>>
 
template<typename Scalar >
using FlyHighResidualDataTpl = typename FlyHighResidualTpl<Scalar>::Data
 
using uint = unsigned int
 

Enumerations

enum struct  RolloutType { LINEAR , NONLINEAR }
 
enum struct  ErrorCode { UNINITIALIZED , UNSUPPORTED_OPTION , NAN_DETECTED }
 
enum struct  HessianApprox { EXACT , GAUSS_NEWTON , BFGS }
 
enum struct  MultiplierUpdateMode { NEWTON , PRIMAL , PRIMAL_DUAL }
 
enum struct  LinesearchMode { PRIMAL = 0 , PRIMAL_DUAL = 1 }
 Whether to use merit functions in primal or primal-dual mode. More...
 
enum struct  StepAcceptanceStrategy { LINESEARCH = 0 , FILTER = 1 }
 Whether to use linesearch or filter during step acceptance phase. More...
 
enum class  LQSolverChoice { SERIAL , PARALLEL , STAGEDENSE }
 

Functions

template<typename S >
std::ostream & operator<< (std::ostream &oss, const ExplicitDynamicsDataTpl< S > &self)
 
template<typename Scalar >
std::ostream & operator<< (std::ostream &oss, const ResultsBaseTpl< Scalar > &self)
 
template<typename Scalar >
void xs_default_init (const TrajOptProblemTpl< Scalar > &problem, std::vector< typename math_types< Scalar >::VectorXs > &xs)
 Default-intialize 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 >
auto problemInitializeSolution (const TrajOptProblemTpl< Scalar > &problem)
 
template<typename Scalar >
void check_trajectory_and_assign (const TrajOptProblemTpl< Scalar > &problem, const typename math_types< Scalar >::VectorOfVectors &xs_init, const typename math_types< Scalar >::VectorOfVectors &us_init, 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 T , typename... Args>
auto allocate_shared_eigen_aligned (Args &&...args)
 
template<typename D >
auto eigenPrintWithPreamble (const Eigen::EigenBase< D > &mat, const std::string &text)
 
template<typename Scalar >
auto directSum (shared_ptr< CostAbstractTpl< Scalar > > const &c1, shared_ptr< CostAbstractTpl< Scalar > > const &c2)
 
template<typename T >
shared_ptr< CostStackTpl< T > > operator+ (const CostPtr< T > &c1, const CostPtr< T > &c2)
 
template<typename T >
shared_ptr< CostStackTpl< T > > operator+ (shared_ptr< CostStackTpl< T > > &&c1, const CostPtr< T > &c2)
 
template<typename T >
shared_ptr< CostStackTpl< T > > operator+ (shared_ptr< CostStackTpl< T > > &&c1, CostPtr< T > &&c2)
 
template<typename T >
shared_ptr< CostStackTpl< T > > operator+ (const shared_ptr< CostStackTpl< T > > &c1, CostPtr< T > &&c2)
 
template<typename T >
shared_ptr< CostStackTpl< T > > operator* (T u, const CostPtr< T > &c1)
 
template<typename T >
shared_ptr< CostStackTpl< T > > operator* (T u, shared_ptr< CostStackTpl< T > > &&c1)
 
template<typename Scalar >
auto directSum (shared_ptr< ExplicitDynamicsModelTpl< Scalar > > const &m1, shared_ptr< ExplicitDynamicsModelTpl< Scalar > > const &m2)
 
template<typename Scalar >
auto linear_compose (shared_ptr< 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 (shared_ptr< 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 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)
 
template<typename Scalar >
std::ostream & operator<< (std::ostream &oss, const ResultsTpl< Scalar > &self)
 
template<typename Scalar >
auto getConstraintProductSet (const ConstraintStackTpl< Scalar > &constraints)
 
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< shared_ptr< 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< shared_ptr< 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< shared_ptr< 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.
 
std::string printVersion (const std::string &delimiter=".")
 Pretty-print the package version number.
 
 _process ()
 

Variables

constexpr std::string_view int_format = "{: >{}d}"
 
constexpr std::string_view sci_format = "{: >{}.4e}"
 
constexpr std::string_view dbl_format = "{: >{}.4g}"
 
static const std::array< LogColumn, 11 > BASIC_KEYS
 

Detailed Description

Main package namespace.

Author
Wilson Jallet
Author
Wilson Jallet
Author
Wilson Jallet
Copyright (C) 2022 LAAS-CNRS, INRIA

Typedef Documentation

◆ DynamicsDataTpl

template<typename Scalar >
using aligator::DynamicsDataTpl = StageFunctionDataTpl<Scalar>

Definition at line 62 of file fwd.hpp.

◆ StdVectorEigenAligned

template<typename T >
using aligator::StdVectorEigenAligned = std::vector<T, Eigen::aligned_allocator<T>>

Definition at line 122 of file fwd.hpp.

◆ FlyHighResidualDataTpl

template<typename Scalar >
using aligator::FlyHighResidualDataTpl = typename FlyHighResidualTpl<Scalar>::Data

Definition at line 43 of file fly-high.hpp.

◆ uint

using aligator::uint = unsigned int

Definition at line 11 of file logger.hpp.

Enumeration Type Documentation

◆ RolloutType

enum struct aligator::RolloutType
strong
Enumerator
LINEAR 

Linear rollout.

NONLINEAR 

Nonlinear rollout, using the full dynamics.

Definition at line 5 of file enums.hpp.

◆ ErrorCode

enum struct aligator::ErrorCode
strong
Enumerator
UNINITIALIZED 
UNSUPPORTED_OPTION 
NAN_DETECTED 

Definition at line 12 of file enums.hpp.

◆ HessianApprox

enum struct aligator::HessianApprox
strong
Enumerator
EXACT 

Use exact Hessian.

GAUSS_NEWTON 

Use the Gauss-Newton approximation.

BFGS 

Use a BFGS-type approximation.

Definition at line 14 of file enums.hpp.

◆ MultiplierUpdateMode

enum struct aligator::MultiplierUpdateMode
strong
Enumerator
NEWTON 
PRIMAL 
PRIMAL_DUAL 

Definition at line 23 of file enums.hpp.

◆ LinesearchMode

enum struct aligator::LinesearchMode
strong

Whether to use merit functions in primal or primal-dual mode.

Enumerator
PRIMAL 
PRIMAL_DUAL 

Definition at line 26 of file enums.hpp.

◆ StepAcceptanceStrategy

Whether to use linesearch or filter during step acceptance phase.

Enumerator
LINESEARCH 
FILTER 

Definition at line 29 of file enums.hpp.

◆ LQSolverChoice

enum class aligator::LQSolverChoice
strong
Enumerator
SERIAL 
PARALLEL 
STAGEDENSE 

Definition at line 35 of file solver-proxddp.hpp.

Function Documentation

◆ operator<<() [1/3]

template<typename S >
std::ostream & aligator::operator<< ( std::ostream & oss,
const ExplicitDynamicsDataTpl< S > & self )

Definition at line 85 of file explicit-dynamics.hpp.

◆ operator<<() [2/3]

template<typename Scalar >
std::ostream & aligator::operator<< ( std::ostream & oss,
const ResultsBaseTpl< Scalar > & self )

Definition at line 97 of file results-base.hpp.

◆ xs_default_init()

template<typename Scalar >
void aligator::xs_default_init ( const TrajOptProblemTpl< Scalar > & problem,
std::vector< typename math_types< Scalar >::VectorXs > & xs )

Default-intialize a trajectory to the neutral states for each state space at each stage.

Definition at line 13 of file solver-util.hpp.

◆ us_default_init()

template<typename Scalar >
void aligator::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.

Definition at line 37 of file solver-util.hpp.

◆ problemInitializeSolution()

template<typename Scalar >
auto aligator::problemInitializeSolution ( const TrajOptProblemTpl< Scalar > & problem)

Definition at line 48 of file solver-util.hpp.

◆ check_trajectory_and_assign()

template<typename Scalar >
void aligator::check_trajectory_and_assign ( const TrajOptProblemTpl< Scalar > & problem,
const typename math_types< Scalar >::VectorOfVectors & xs_init,
const typename math_types< Scalar >::VectorOfVectors & us_init,
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.

Definition at line 75 of file solver-util.hpp.

◆ allocate_shared_eigen_aligned()

template<typename T , typename... Args>
auto aligator::allocate_shared_eigen_aligned ( Args &&... args)
inline

Definition at line 125 of file fwd.hpp.

◆ eigenPrintWithPreamble()

template<typename D >
auto aligator::eigenPrintWithPreamble ( const Eigen::EigenBase< D > & mat,
const std::string & text )

Prints an Eigen object using Eigen::IOFormat with a piece of text prepended and all rows shifted by the length of that text.

Definition at line 36 of file math.hpp.

◆ directSum() [1/2]

template<typename Scalar >
auto aligator::directSum ( shared_ptr< CostAbstractTpl< Scalar > > const & c1,
shared_ptr< CostAbstractTpl< Scalar > > const & c2 )

Definition at line 123 of file cost-direct-sum.hpp.

◆ operator+() [1/4]

template<typename T >
shared_ptr< CostStackTpl< T > > aligator::operator+ ( const CostPtr< T > & c1,
const CostPtr< T > & c2 )

Definition at line 65 of file sum-of-costs.hpp.

◆ operator+() [2/4]

template<typename T >
shared_ptr< CostStackTpl< T > > aligator::operator+ ( shared_ptr< CostStackTpl< T > > && c1,
const CostPtr< T > & c2 )

Definition at line 71 of file sum-of-costs.hpp.

◆ operator+() [3/4]

template<typename T >
shared_ptr< CostStackTpl< T > > aligator::operator+ ( shared_ptr< CostStackTpl< T > > && c1,
CostPtr< T > && c2 )

Definition at line 78 of file sum-of-costs.hpp.

◆ operator+() [4/4]

template<typename T >
shared_ptr< CostStackTpl< T > > aligator::operator+ ( const shared_ptr< CostStackTpl< T > > & c1,
CostPtr< T > && c2 )

Definition at line 85 of file sum-of-costs.hpp.

◆ operator*() [1/2]

template<typename T >
shared_ptr< CostStackTpl< T > > aligator::operator* ( T u,
const CostPtr< T > & c1 )

Definition at line 92 of file sum-of-costs.hpp.

◆ operator*() [2/2]

template<typename T >
shared_ptr< CostStackTpl< T > > aligator::operator* ( T u,
shared_ptr< CostStackTpl< T > > && c1 )

Definition at line 97 of file sum-of-costs.hpp.

◆ directSum() [2/2]

template<typename Scalar >
auto aligator::directSum ( shared_ptr< ExplicitDynamicsModelTpl< Scalar > > const & m1,
shared_ptr< ExplicitDynamicsModelTpl< Scalar > > const & m2 )

Definition at line 53 of file explicit-dynamics-direct-sum.hpp.

◆ linear_compose() [1/2]

template<typename Scalar >
auto aligator::linear_compose ( shared_ptr< 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.

Definition at line 108 of file linear-function-composition.hpp.

◆ linear_compose() [2/2]

template<typename Scalar >
auto aligator::linear_compose ( shared_ptr< 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.

Definition at line 116 of file linear-function-composition.hpp.

◆ underactuatedConstrainedInverseDynamics()

template<typename Scalar , typename ConfigType , typename VelType , typename MatrixType , typename OutType , int Options>
void aligator::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_ )

Definition at line 22 of file constrained-rnea.hpp.

◆ fddp_goldstein_linesearch()

template<typename Scalar , typename F , typename M >
ALIGATOR_INLINE std::pair< Scalar, Scalar > aligator::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).

The conditions that are checked for are not exactly the Goldstein conditions.

Returns
an std::pair

Definition at line 15 of file linesearch.hpp.

◆ costDirectionalDerivative()

template<typename Scalar >
Scalar aligator::costDirectionalDerivative ( const WorkspaceTpl< Scalar > & workspace,
const TrajOptDataTpl< Scalar > & prob_data )

◆ operator<<() [3/3]

template<typename Scalar >
std::ostream & aligator::operator<< ( std::ostream & oss,
const ResultsTpl< Scalar > & self )

Definition at line 41 of file results.hpp.

◆ getConstraintProductSet()

template<typename Scalar >
auto aligator::getConstraintProductSet ( const ConstraintStackTpl< Scalar > & constraints)

Definition at line 18 of file workspace.hpp.

◆ rotate_vec_left()

template<typename T , typename Alloc >
void aligator::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 Parameters
T
Alloc
Parameters
n_headThe length of the vector (at the head) to keep.
n_tailThe length of the vector (at the tail ) to keep.

Definition at line 17 of file mpc-util.hpp.

◆ rollout() [1/6]

template<typename Scalar >
math_types< Scalar >::VectorOfVectors aligator::rollout ( const std::vector< shared_ptr< 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.

Definition at line 10 of file rollout.hpp.

◆ rollout() [2/6]

template<typename Scalar >
math_types< Scalar >::VectorOfVectors aligator::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.

Definition at line 36 of file rollout.hpp.

◆ rollout() [3/6]

template<typename Scalar >
void aligator::rollout ( const std::vector< shared_ptr< 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.

This overload applies to explicit forward dynamics.

Definition at line 57 of file rollout.hpp.

◆ rollout() [4/6]

template<typename Scalar >
void aligator::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.

Definition at line 83 of file rollout.hpp.

◆ rollout() [5/6]

template<template< typename > class C, typename Scalar >
math_types< Scalar >::VectorOfVectors aligator::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.

Definition at line 103 of file rollout.hpp.

◆ rollout() [6/6]

template<template< typename > class C, typename Scalar >
math_types< Scalar >::VectorOfVectors aligator::rollout ( const std::vector< shared_ptr< 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.

Definition at line 115 of file rollout.hpp.

◆ printVersion()

std::string aligator::printVersion ( const std::string & delimiter = ".")
inline

Pretty-print the package version number.

Parameters
delimiterThe delimiter between the major/minor/patch version components.

Definition at line 13 of file version.hpp.

◆ _process()

aligator._process ( )
protected

Definition at line 15 of file __init__.py.

Variable Documentation

◆ int_format

constexpr std::string_view aligator::int_format = "{: >{}d}"
constexpr

Definition at line 13 of file logger.hpp.

◆ sci_format

constexpr std::string_view aligator::sci_format = "{: >{}.4e}"
constexpr

Definition at line 14 of file logger.hpp.

◆ dbl_format

constexpr std::string_view aligator::dbl_format = "{: >{}.4g}"
constexpr

Definition at line 15 of file logger.hpp.

◆ BASIC_KEYS

const std::array<LogColumn, 11> aligator::BASIC_KEYS
static
Initial value:
= {
{{"iter", int_format, 5U},
{"alpha", sci_format, 10U},
{"inner_crit", sci_format, 10U},
{"prim_err", sci_format, 10U},
{"dual_err", sci_format, 10U},
{"preg", sci_format, 10U},
{"dphi0", sci_format, 11U},
{"merit", sci_format, 11U},
{"ΔM", sci_format, 11U},
{"aliter", int_format, 7U},
{"mu", dbl_format, 8U}}}
constexpr std::string_view sci_format
Definition logger.hpp:14
constexpr std::string_view dbl_format
Definition logger.hpp:15
constexpr std::string_view int_format
Definition logger.hpp:13

Definition at line 23 of file logger.hpp.