aligator  0.16.0
A versatile and efficient C++ library for real-time constrained trajectory optimization.
Loading...
Searching...
No Matches
stage-model.hpp
Go to the documentation of this file.
1
3#pragma once
4
7
8namespace aligator {
9using xyz::polymorphic;
10
11#define ALIGATOR_CHECK_DERIVED_CLASS(Base, Derived) \
12 static_assert((std::is_base_of_v<Base, Derived>), \
13 "Failed check for derived class.")
14
22template <typename _Scalar> struct StageModelTpl {
23public:
24 using Scalar = _Scalar;
26
28 using PolyManifold = polymorphic<Manifold>;
30 using PolyDynamics = polymorphic<Dynamics>;
31 using PolyFunction = polymorphic<StageFunctionTpl<Scalar>>;
32 using PolyConstraintSet = polymorphic<ConstraintSetTpl<Scalar>>;
34 using PolyCost = polymorphic<Cost>;
36
49
51 template <typename U> U *getCost() {
53 return dynamic_cast<U *>(&*cost_);
54 }
55
57 template <typename U> const U *getCost() const {
59 return dynamic_cast<const U *>(&*cost_);
60 }
61
63 template <typename U> U *getDynamics() {
65 return dynamic_cast<U *>(&*dynamics_);
66 }
67
69 template <typename U> const U *getDynamics() const {
71 return dynamic_cast<const U *>(&*dynamics_);
72 }
73
77 virtual ~StageModelTpl() = default;
78
79 const Manifold &xspace() const { return *xspace_; }
80 const Manifold &uspace() const { return *uspace_; }
81 const Manifold &xspace_next() const { return *xspace_next_; }
82
83 const Cost &cost() const { return *cost_; }
87 virtual bool hasDynModel() const { return true; }
88
89 int nx1() const { return xspace_->nx(); }
90 int ndx1() const { return xspace_->ndx(); }
91 int nu() const { return uspace_->ndx(); }
92 int nx2() const { return xspace_next_->nx(); }
93 int ndx2() const { return xspace_next_->ndx(); }
95 int nc() const { return (int)constraints_.totalDim(); }
96
98 std::size_t numConstraints() const { return constraints_.size(); }
99
101 int numDual() const { return ndx2() + nc(); }
102
104 void addConstraint(const PolyFunction &func,
105 const PolyConstraintSet &cstr_set);
106
107 /* Evaluate costs, constraints, ... */
108
111 virtual void evaluate(const ConstVectorRef &x, const ConstVectorRef &u,
112 Data &data) const;
113
115 virtual void computeFirstOrderDerivatives(const ConstVectorRef &x,
116 const ConstVectorRef &u,
117 Data &data) const;
118
120 virtual void computeSecondOrderDerivatives(const ConstVectorRef &x,
121 const ConstVectorRef &u,
122 Data &data) const;
123
125 virtual shared_ptr<Data> createData() const;
126};
127
128#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
129extern template struct StageModelTpl<context::Scalar>;
130#endif
131
132} // namespace aligator
133
134template <typename Scalar>
135struct fmt::formatter<aligator::StageModelTpl<Scalar>> {
136 constexpr auto parse(format_parse_context &ctx) const
137 -> decltype(ctx.begin()) {
138 return ctx.end();
139 }
140
141 auto format(const aligator::StageModelTpl<Scalar> &stage,
142 format_context &ctx) const -> decltype(ctx.out()) {
143 if (stage.ndx1() == stage.ndx2()) {
144 return fmt::format_to(ctx.out(),
145 "StageModel {{"
146 "\n ndx: {:d},"
147 "\n nu: {:d},"
148 "\n nc: {:d}, [{:d} constraints]"
149 "\n}}",
150 stage.ndx1(), stage.nu(), stage.nc(),
151 stage.numConstraints());
152 } else {
153 return fmt::format_to(ctx.out(),
154 "StageModel {{"
155 "\n ndx1: {:d},"
156 "\n nu: {:d},"
157 "\n nc: {:d}, [{:d} constraints]"
158 "\n ndx2: {:d},"
159 "\n}}",
160 stage.ndx1(), stage.nu(), stage.nc(),
161 stage.numConstraints(), stage.ndx2());
162 }
163 }
164};
165
166namespace aligator {
167template <typename Scalar>
168std::ostream &operator<<(std::ostream &oss, const StageModelTpl<Scalar> &sm) {
169 return oss << fmt::format("{}", sm);
170}
171} // namespace aligator
Defines the constraint object and constraint stack manager for this library.
Base definitions for ternary functions.
Namespace for modelling system dynamics.
Main package namespace.
std::ostream & operator<<(std::ostream &oss, const StageFunctionDataTpl< T > &self)
#define ALIGATOR_CHECK_DERIVED_CLASS(Base, Derived)
Convenience class to manage a stack of constraints.
Stage costs for control problems.
Explicit forward dynamics model .
Base class for manifolds, to use in cost funcs, solvers...
Data struct for stage models StageModelTpl.
A stage in the control problem.
virtual ~StageModelTpl()=default
const U * getCost() const
CostAbstractTpl< Scalar > Cost
virtual void computeFirstOrderDerivatives(const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const
Compute the first-order derivatives of the StageModelTpl.
U * getDynamics()
Get a pointer to an expected concrete type for the dynamics class.
virtual bool hasDynModel() const
virtual void computeSecondOrderDerivatives(const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const
Compute the second-order derivatives of the StageModelTpl.
const Manifold & xspace_next() const
polymorphic< Manifold > PolyManifold
ManifoldAbstractTpl< Scalar > Manifold
ConstraintStackTpl< Scalar > constraints_
virtual void evaluate(const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const
Evaluate all the functions (cost, dynamics, constraints) at this node.
polymorphic< ConstraintSetTpl< Scalar > > PolyConstraintSet
ExplicitDynamicsModelTpl< Scalar > Dynamics
StageModelTpl(const PolyCost &cost, const PolyDynamics &dynamics)
virtual shared_ptr< Data > createData() const
Create a StageData object.
const Manifold & uspace() const
StageDataTpl< Scalar > Data
int numDual() const
Number of dual variables, i.e. Lagrange multipliers.
void addConstraint(const PolyFunction &func, const PolyConstraintSet &cstr_set)
Add a constraint to the stage.
const U * getDynamics() const
U * getCost()
Get a pointer to an expected concrete type for the cost function.
polymorphic< Dynamics > PolyDynamics
std::size_t numConstraints() const
Number of constraint objects.
const Manifold & xspace() const
polymorphic< StageFunctionTpl< Scalar > > PolyFunction
int nc() const
Total number of constraints.