aligator  0.9.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
action-model-wrap.hpp
Go to the documentation of this file.
1
3#pragma once
4
8
12#include <crocoddyl/core/action-base.hpp>
13
14namespace aligator {
15namespace compat {
16namespace croc {
17template <typename Scalar>
18struct NoOpDynamics final : DynamicsModelTpl<Scalar> {
21 using Manifold = ManifoldAbstractTpl<Scalar>;
23 NoOpDynamics(xyz::polymorphic<Manifold> state, const int nu)
24 : Base(state, nu) {}
25
26 void evaluate(const ConstVectorRef &, const ConstVectorRef &,
27 const ConstVectorRef &, DynData &) const override {}
28
29 void computeJacobians(const ConstVectorRef &, const ConstVectorRef &,
30 const ConstVectorRef &, DynData &) const override {}
31};
32
38template <typename Scalar>
39struct ActionModelWrapperTpl : StageModelTpl<Scalar> {
44 using CrocActionModel = crocoddyl::ActionModelAbstractTpl<Scalar>;
48 using Manifold = ManifoldAbstractTpl<Scalar>;
49
50 boost::shared_ptr<CrocActionModel> action_model_;
51
53 boost::shared_ptr<CrocActionModel> action_model);
54
55 bool hasDynModel() const override { return false; }
56
57 void evaluate(const ConstVectorRef &x, const ConstVectorRef &u,
58 const ConstVectorRef &y, Data &data) const override;
59
60 void computeFirstOrderDerivatives(const ConstVectorRef &x,
61 const ConstVectorRef &u,
62 const ConstVectorRef &y,
63 Data &data) const override;
64
66 void computeSecondOrderDerivatives(const ConstVectorRef & /*x*/,
67 const ConstVectorRef & /*u*/,
68 Data & /*data*/) const override {}
69
70 shared_ptr<Data> createData() const override;
71};
72
77template <typename Scalar>
78struct ActionDataWrapperTpl : public StageDataTpl<Scalar> {
80 using CrocActionModel = crocoddyl::ActionModelAbstractTpl<Scalar>;
81 using CrocActionData = crocoddyl::ActionDataAbstractTpl<Scalar>;
83
84 boost::shared_ptr<CrocActionData> croc_action_data;
85
87
88 void checkData();
89
90protected:
91 // utility pointer
92 shared_ptr<DynamicsDataWrapper> dynamics_data;
94};
95
96} // namespace croc
97} // namespace compat
98} // namespace aligator
99
100#include "aligator/compat/crocoddyl/action-model-wrap.txx"
Main package namespace.
Stage costs for control problems.
Definition fwd.hpp:65
Dynamics model: describes system dynamics through an implicit relation .
Definition fwd.hpp:71
const int nu
Control dimension.
Definition dynamics.hpp:27
Data struct for stage models StageModelTpl.
Definition fwd.hpp:96
A stage in the control problem.
Definition fwd.hpp:93
A complicated child class to StageDataTpl which pipes Crocoddyl's data to the right places.
Definition fwd.hpp:21
crocoddyl::ActionModelAbstractTpl< Scalar > CrocActionModel
crocoddyl::ActionDataAbstractTpl< Scalar > CrocActionData
shared_ptr< DynamicsDataWrapper > dynamics_data
boost::shared_ptr< CrocActionData > croc_action_data
ActionDataWrapperTpl(const ActionModelWrapperTpl< Scalar > &croc_action_model)
void checkData()
Check data integrity.
Wraps a crocoddyl::ActionModelAbstract.
Definition fwd.hpp:19
void computeFirstOrderDerivatives(const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &y, Data &data) const override
Compute the first-order derivatives of the StageModelTpl.
ActionModelWrapperTpl(boost::shared_ptr< CrocActionModel > action_model)
void evaluate(const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &y, Data &data) const override
Evaluate all the functions (cost, dynamics, constraints) at this node.
boost::shared_ptr< CrocActionModel > action_model_
void computeSecondOrderDerivatives(const ConstVectorRef &, const ConstVectorRef &, Data &) const override
Does nothing for this class.
crocoddyl::ActionModelAbstractTpl< Scalar > CrocActionModel
shared_ptr< Data > createData() const override
Create a StageData object.
NoOpDynamics(xyz::polymorphic< Manifold > state, const int nu)
void evaluate(const ConstVectorRef &, const ConstVectorRef &, const ConstVectorRef &, DynData &) const override
void computeJacobians(const ConstVectorRef &, const ConstVectorRef &, const ConstVectorRef &, DynData &) const override
ManifoldAbstractTpl< Scalar > Manifold
Wraps a crocoddyl::StateAbstractTpl to a manifold (proxsuite::nlp::ManifoldAbstractTpl).