aligator  0.6.1
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
10#include <crocoddyl/core/action-base.hpp>
11
12namespace aligator {
13namespace compat {
14namespace croc {
15
21template <typename Scalar>
24 using Base = StageModelTpl<Scalar>;
25 using Data = StageDataTpl<Scalar>;
26 using Constraint = StageConstraintTpl<Scalar>;
27 using Dynamics = typename Base::Dynamics;
28 using CrocActionModel = crocoddyl::ActionModelAbstractTpl<Scalar>;
29 using StateWrapper = StateWrapperTpl<Scalar>;
30 using ActionDataWrap = ActionDataWrapperTpl<Scalar>;
31 using DynDataWrap = DynamicsDataWrapperTpl<Scalar>;
32
33 boost::shared_ptr<CrocActionModel> action_model_;
34
36 boost::shared_ptr<CrocActionModel> action_model);
37
38 bool has_dyn_model() const override { return false; }
39
40 void evaluate(const ConstVectorRef &x, const ConstVectorRef &u,
41 const ConstVectorRef &y, Data &data) const override;
42
43 void computeFirstOrderDerivatives(const ConstVectorRef &x,
44 const ConstVectorRef &u,
45 const ConstVectorRef &y,
46 Data &data) const override;
47
49 void computeSecondOrderDerivatives(const ConstVectorRef & /*x*/,
50 const ConstVectorRef & /*u*/,
51 Data & /*data*/) const override {}
52
53 shared_ptr<Data> createData() const override;
54};
55
60template <typename Scalar>
61struct ActionDataWrapperTpl : public StageDataTpl<Scalar> {
62 using Base = StageDataTpl<Scalar>;
63 using CrocActionModel = crocoddyl::ActionModelAbstractTpl<Scalar>;
64 using CrocActionData = crocoddyl::ActionDataAbstractTpl<Scalar>;
65 using DynamicsDataWrapper = DynamicsDataWrapperTpl<Scalar>;
66
67 boost::shared_ptr<CrocActionData> croc_action_data;
68
70 const boost::shared_ptr<CrocActionModel> &croc_action_model);
71
72 void checkData();
73
74protected:
75 // utility pointer
76 shared_ptr<DynamicsDataWrapper> dynamics_data;
77 friend ActionModelWrapperTpl<Scalar>;
78};
79
80} // namespace croc
81} // namespace compat
82} // namespace aligator
83
84#include "aligator/compat/crocoddyl/action-model-wrap.hxx"
Main package namespace.
A stage in the control problem.
DynamicsModelTpl< Scalar > Dynamics
A complicated child class to StageDataTpl which pipes Crocoddyl's data to the right places.
DynamicsDataWrapperTpl< Scalar > DynamicsDataWrapper
crocoddyl::ActionModelAbstractTpl< Scalar > CrocActionModel
crocoddyl::ActionDataAbstractTpl< Scalar > CrocActionData
shared_ptr< DynamicsDataWrapper > dynamics_data
boost::shared_ptr< CrocActionData > croc_action_data
ActionDataWrapperTpl(const boost::shared_ptr< CrocActionModel > &croc_action_model)
void checkData()
Check data integrity.
Wraps a crocoddyl::ActionModelAbstract.
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_
DynamicsDataWrapperTpl< Scalar > DynDataWrap
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.