12#include <crocoddyl/core/action-base.hpp>
17template <
typename Scalar>
26 void evaluate(
const ConstVectorRef &,
const ConstVectorRef &,
27 const ConstVectorRef &,
DynData &)
const override {}
30 const ConstVectorRef &,
DynData &)
const override {}
38template <
typename Scalar>
53 boost::shared_ptr<CrocActionModel> action_model);
57 void evaluate(
const ConstVectorRef &x,
const ConstVectorRef &u,
58 const ConstVectorRef &y,
Data &data)
const override;
61 const ConstVectorRef &u,
62 const ConstVectorRef &y,
63 Data &data)
const override;
67 const ConstVectorRef & ,
68 Data & )
const override {}
77template <
typename Scalar>
100#include "aligator/compat/crocoddyl/action-model-wrap.txx"
Stage costs for control problems.
Dynamics model: describes system dynamics through an implicit relation .
const int nu
Control dimension.
Data struct for stage models StageModelTpl.
A stage in the control problem.
A complicated child class to StageDataTpl which pipes Crocoddyl's data to the right places.
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.
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_
ManifoldAbstractTpl< Scalar > Manifold
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
bool hasDynModel() const override
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
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
void computeJacobians(const ConstVectorRef &, const ConstVectorRef &, const ConstVectorRef &, DynData &) const override
ManifoldAbstractTpl< Scalar > Manifold
Wraps a crocoddyl::StateAbstractTpl to a manifold (proxsuite::nlp::ManifoldAbstractTpl).