10#include <crocoddyl/core/action-base.hpp>
21template <
typename Scalar>
24 using Base = StageModelTpl<Scalar>;
25 using Data = StageDataTpl<Scalar>;
36 boost::shared_ptr<CrocActionModel> action_model);
40 void evaluate(
const ConstVectorRef &x,
const ConstVectorRef &u,
41 const ConstVectorRef &y,
Data &data)
const override;
44 const ConstVectorRef &u,
45 const ConstVectorRef &y,
46 Data &data)
const override;
50 const ConstVectorRef & ,
51 Data & )
const override {}
60template <
typename Scalar>
62 using Base = StageDataTpl<Scalar>;
70 const boost::shared_ptr<CrocActionModel> &croc_action_model);
77 friend ActionModelWrapperTpl<Scalar>;
84#include "aligator/compat/crocoddyl/action-model-wrap.hxx"
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)
StageConstraintTpl< Scalar > Constraint
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.
ActionDataWrapperTpl< Scalar > ActionDataWrap
boost::shared_ptr< CrocActionModel > action_model_
bool has_dyn_model() const override
StateWrapperTpl< Scalar > StateWrapper
DynamicsDataWrapperTpl< Scalar > DynDataWrap
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
typename Base::Dynamics Dynamics
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.