aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
fwd.hpp
Go to the documentation of this file.
1
4#pragma once
5
6#include <proxsuite-nlp/fwd.hpp>
7
8#ifdef ALIGATOR_WITH_PINOCCHIO
9#include <pinocchio/config.hpp>
10#if PINOCCHIO_VERSION_AT_LEAST(2, 9, 2)
11#define ALIGATOR_PINOCCHIO_V3
12#endif
13#endif
14
15#include "aligator/math.hpp"
16#include "aligator/macros.hpp"
18#include "aligator/config.hpp"
19#include "aligator/deprecated.hpp"
20
22namespace aligator {
24
25// NOLINTBEGIN(misc-unused-using-decls)
26
27// Use the shared_ptr used in proxsuite-nlp.
28using proxsuite::nlp::BCLParamsTpl;
29using proxsuite::nlp::ConstraintSetBase;
30using proxsuite::nlp::ManifoldAbstractTpl;
31// Use the math_types template from proxsuite-nlp.
32using proxsuite::nlp::VerboseLevel;
33
34using VerboseLevel::QUIET;
35using VerboseLevel::VERBOSE;
36using VerboseLevel::VERYVERBOSE;
37
38using std::shared_ptr;
39using std::unique_ptr;
40
41// NOLINTEND(misc-unused-using-decls)
42
43// fwd StageFunctionTpl
44template <typename Scalar> struct StageFunctionTpl;
45
46// fwd UnaryFunctionTpl
47template <typename Scalar> struct UnaryFunctionTpl;
48
49// fwd StageFunctionDataTpl
50template <typename Scalar> struct StageFunctionDataTpl;
51
52// fwd CostAbstractTpl
53template <typename Scalar> struct CostAbstractTpl;
54
55// fwd CostDataAbstractTpl
56template <typename Scalar> struct CostDataAbstractTpl;
57
58// fwd DynamicsModelTpl
59template <typename Scalar> struct DynamicsModelTpl;
60
61// fwd DynamicsDataTpl
62template <typename Scalar> using DynamicsDataTpl = StageFunctionDataTpl<Scalar>;
63
64// fwd StageConstraintTpl
65template <typename Scalar> struct StageConstraintTpl;
66
67// fwd ExplicitDynamicsModelTpl
68template <typename Scalar> struct ExplicitDynamicsModelTpl;
69
70// fwd declaration of ExplicitDynamicsDataTpl
71template <typename Scalar> struct ExplicitDynamicsDataTpl;
72
73/* FUNCTION EXPRESSIONS */
74
75// fwd declaration of FunctionSliceXprTpl
76template <typename Scalar, typename Base> struct FunctionSliceXprTpl;
77
78/* STAGE MODEL */
79
80// fwd StageModelTpl
81template <typename Scalar> struct StageModelTpl;
82
83// fwd StageDataTpl
84template <typename Scalar> struct StageDataTpl;
85
86// fwd CallbackBaseTpl
87template <typename Scalar> struct CallbackBaseTpl;
88
89/* SHOOTING PROBLEM */
90
91// fwd ConstraintStackTpl
92template <typename Scalar> struct ConstraintStackTpl;
93
94// fwd TrajOptProblemTpl
95template <typename Scalar> struct TrajOptProblemTpl;
96
97// fwd TrajOptDataTpl
98template <typename Scalar> struct TrajOptDataTpl;
99
100// fwd SolverProxDDP
101template <typename Scalar> struct SolverProxDDPTpl;
102
103// fwd SolverFDDP
104template <typename Scalar> struct SolverFDDPTpl;
105
106// fwd WorkspaceBaseTpl
107template <typename Scalar> struct WorkspaceBaseTpl;
108
109// fwd ResultsBaseTpl
110template <typename Scalar> struct ResultsBaseTpl;
111
112// fwd WorkspaceTpl
113template <typename Scalar> struct WorkspaceTpl;
114
115// fwd ResultsTpl
116template <typename Scalar> struct ResultsTpl;
117
118// fwd FilterTpl
119template <typename Scalar> struct FilterTpl;
120
121template <typename T>
122using StdVectorEigenAligned = std::vector<T, Eigen::aligned_allocator<T>>;
123
124template <typename T, typename... Args>
125inline auto allocate_shared_eigen_aligned(Args &&...args) {
126 return std::allocate_shared<T>(Eigen::aligned_allocator<T>(),
127 std::forward<Args>(args)...);
128}
129
130} // namespace aligator
Math utilities.
Main package namespace.
std::vector< T, Eigen::aligned_allocator< T > > StdVectorEigenAligned
Definition fwd.hpp:122
auto allocate_shared_eigen_aligned(Args &&...args)
Definition fwd.hpp:125
Base callback class.
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.
Definition filter.hpp:12
Represents a function of which the output is a subset of another function, for instance where is gi...
Results holder struct.
Definition results.hpp:10
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.
Problem data struct.
Trajectory optimization problem.
Base workspace struct for the algorithms.
Workspace for solver SolverProxDDP.
Definition workspace.hpp:30