6#include <proxsuite-nlp/fwd.hpp>
8#ifdef ALIGATOR_WITH_PINOCCHIO
9#include <pinocchio/config.hpp>
10#if PINOCCHIO_VERSION_AT_LEAST(2, 9, 2)
11#define ALIGATOR_PINOCCHIO_V3
18#include "aligator/config.hpp"
19#include "aligator/deprecated.hpp"
28using proxsuite::nlp::BCLParamsTpl;
29using proxsuite::nlp::ConstraintSetBase;
30using proxsuite::nlp::ManifoldAbstractTpl;
32using proxsuite::nlp::VerboseLevel;
34using VerboseLevel::QUIET;
35using VerboseLevel::VERBOSE;
36using VerboseLevel::VERYVERBOSE;
44template <
typename Scalar>
struct StageFunctionTpl;
47template <
typename Scalar>
struct UnaryFunctionTpl;
50template <
typename Scalar>
struct StageFunctionDataTpl;
53template <
typename Scalar>
struct CostAbstractTpl;
56template <
typename Scalar>
struct CostDataAbstractTpl;
59template <
typename Scalar>
struct DynamicsModelTpl;
119template <
typename Scalar>
struct FilterTpl;
124template <
typename T,
typename... Args>
126 return std::allocate_shared<T>(Eigen::aligned_allocator<T>(),
127 std::forward<Args>(args)...);
std::vector< T, Eigen::aligned_allocator< T > > StdVectorEigenAligned
auto allocate_shared_eigen_aligned(Args &&...args)
Convenience class to manage a stack of constraints.
Specific data struct for explicit dynamics ExplicitDynamicsModelTpl.
Explicit forward dynamics model .
A basic filter line-search strategy.
Represents a function of which the output is a subset of another function, for instance where is gi...
The feasible DDP (FDDP) algorithm, from Mastalli et al. (2020).
A proximal, augmented Lagrangian-type solver for trajectory optimization.
Simple struct holding together a function and set, to describe a constraint.
Data struct for stage models StageModelTpl.
A stage in the control problem.
Trajectory optimization problem.
Base workspace struct for the algorithms.
Workspace for solver SolverProxDDP.