aligator  0.14.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
rollout.hpp
Go to the documentation of this file.
1#pragma once
2
4
5namespace aligator {
6
8template <typename Scalar>
10 const std::vector<xyz::polymorphic<DynamicsModelTpl<Scalar>>> &dyn_models,
11 const typename math_types<Scalar>::VectorXs &x0,
12 const typename math_types<Scalar>::VectorOfVectors &us,
14 using Data = DynamicsDataTpl<Scalar>;
15 const std::size_t N = us.size();
16 if (dyn_models.size() != N) {
18 "Number of controls should be the same as number of dynamical models!");
19 }
20 xout.resize(N + 1);
21 xout[0] = x0;
22
23 for (std::size_t i = 0; i < N; i++) {
24 shared_ptr<Data> data = dyn_models[i]->createData();
25 const ManifoldAbstractTpl<Scalar> &space = dyn_models[i]->space();
26 xout.push_back(space.neutral());
27 forwardDynamics<Scalar>::run(*dyn_models[i], xout[i], us[i], *data,
28 xout[i + 1]);
29 }
30 return xout;
31}
32
34template <typename Scalar>
35typename math_types<Scalar>::VectorOfVectors
37 const typename math_types<Scalar>::VectorXs &x0,
38 const typename math_types<Scalar>::VectorOfVectors &us) {
39 using VectorXs = typename math_types<Scalar>::VectorXs;
40
41 const std::size_t N = us.size();
42 std::vector<VectorXs> xs{x0};
43 xs.reserve(N + 1);
44 shared_ptr<DynamicsDataTpl<Scalar>> data = dyn_model.createData();
45
46 for (std::size_t i = 0; i < N; i++) {
47 const ManifoldAbstractTpl<Scalar> &space = dyn_model.space();
48 xs.push_back(space.neutral());
49 forwardDynamics<Scalar>::run(dyn_model, xs[i], us[i], *data, xs[i + 1]);
50 }
51 return xs;
52}
53
56template <typename Scalar>
59 &dyn_models,
60 const typename math_types<Scalar>::VectorXs &x0,
61 const typename math_types<Scalar>::VectorOfVectors &us,
63 using DataType = ExplicitDynamicsDataTpl<Scalar>;
64 const std::size_t N = us.size();
65 xout.resize(N + 1);
66 xout[0] = x0;
67 if (dyn_models.size() != N) {
68 ALIGATOR_RUNTIME_ERROR("Number of controls ({:d}) should be the same as "
69 "number of dynamical models ({:d})!",
70 N, dyn_models.size());
71 }
72
73 for (std::size_t i = 0; i < N; i++) {
74 shared_ptr<DataType> data =
75 std::static_pointer_cast<DataType>(dyn_models[i]->createData());
76 dyn_models[i]->forward(xout[i], us[i], *data);
77 xout[i + 1] = data->xnext_;
78 }
79}
80
82template <typename Scalar>
84 const typename math_types<Scalar>::VectorXs &x0,
85 const typename math_types<Scalar>::VectorOfVectors &us,
87 using DataType = ExplicitDynamicsDataTpl<Scalar>;
88 const std::size_t N = us.size();
89 xout.resize(N + 1);
90 xout[0] = x0;
91
92 shared_ptr<DataType> data =
93 std::static_pointer_cast<DataType>(dyn_model.createData());
94 for (std::size_t i = 0; i < N; i++) {
95 dyn_model.forward(xout[i], us[i], *data);
96 xout[i + 1] = data->xnext_;
97 }
98}
99
101template <template <typename> class C, typename Scalar>
102typename math_types<Scalar>::VectorOfVectors
103rollout(const C<Scalar> &dms, const typename math_types<Scalar>::VectorXs &x0,
104 const typename math_types<Scalar>::VectorOfVectors &us) {
105 const std::size_t N = us.size();
107 xout.reserve(N + 1);
108 rollout(dms, x0, us, xout);
109 return xout;
110}
111
113template <template <typename> class C, typename Scalar>
114typename math_types<Scalar>::VectorOfVectors
115rollout(const std::vector<xyz::polymorphic<C<Scalar>>> &dms,
116 const typename math_types<Scalar>::VectorXs &x0,
117 const typename math_types<Scalar>::VectorOfVectors &us) {
118 const std::size_t N = us.size();
120 xout.reserve(N + 1);
121 rollout(dms, x0, us, xout);
122 return xout;
123}
124
125} // namespace aligator
#define ALIGATOR_RUNTIME_ERROR(...)
Definition exceptions.hpp:7
Main package namespace.
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.
Definition rollout.hpp:9
Dynamics model: describes system dynamics through an implicit relation .
Definition dynamics.hpp:14
const Manifold & space() const
State space for the input.
Definition dynamics.hpp:32
virtual shared_ptr< Data > createData() const
Specific data struct for explicit dynamics ExplicitDynamicsModelTpl.
Explicit forward dynamics model .
virtual shared_ptr< BaseData > createData() const
virtual void forward(const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const =0
Evaluate the forward discrete dynamics.
Base class for manifolds, to use in cost funcs, solvers...
VectorXs neutral() const
Get the neutral element from the manifold (if this makes sense).
static void run(const DynamicsModelTpl< T > &model, const ConstVectorRef &x, const ConstVectorRef &u, DynamicsDataTpl< T > &data, VectorRef xout, const std::optional< ConstVectorRef > &gap=std::nullopt, const uint max_iters=1000, const T EPS=1e-6)
Typedefs for math (Eigen vectors, matrices) depending on scalar type.
Definition math.hpp:100