crocoddyl  1.6.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
ActionModelImpulseFwdDynamicsTpl< _Scalar > Class Template Reference
Inheritance diagram for ActionModelImpulseFwdDynamicsTpl< _Scalar >:
Collaboration diagram for ActionModelImpulseFwdDynamicsTpl< _Scalar >:

Public Types

typedef ActionDataAbstractTpl< Scalar > ActionDataAbstract
 
typedef ActionModelAbstractTpl< Scalar > Base
 
typedef CostModelSumTpl< Scalar > CostModelSum
 
typedef ActionDataImpulseFwdDynamicsTpl< Scalar > Data
 
typedef ImpulseModelMultipleTpl< Scalar > ImpulseModelMultiple
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef StateMultibodyTpl< Scalar > StateMultibody
 
typedef MathBase::VectorXs VectorXs
 
- Public Types inherited from ActionModelAbstractTpl< _Scalar >
typedef ActionDataAbstractTpl< Scalar > ActionDataAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 ActionModelImpulseFwdDynamicsTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ImpulseModelMultiple > impulses, boost::shared_ptr< CostModelSum > costs, const Scalar &r_coeff=Scalar(0.), const Scalar &JMinvJt_damping=Scalar(0.), const bool &enable_force=false)
 
virtual void calc (const boost::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the next state and cost value. More...
 
virtual void calcDiff (const boost::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the derivatives of the dynamics and cost functions. More...
 
virtual bool checkData (const boost::shared_ptr< ActionDataAbstract > &data)
 Checks that a specific data belongs to this model.
 
virtual boost::shared_ptr< ActionDataAbstractcreateData ()
 Create the action data. More...
 
const VectorXs & get_armature () const
 
const boost::shared_ptr< CostModelSum > & get_costs () const
 
const Scalar & get_damping_factor () const
 
const boost::shared_ptr< ImpulseModelMultiple > & get_impulses () const
 
pinocchio::ModelTpl< Scalar > & get_pinocchio () const
 
const Scalar & get_restitution_coefficient () const
 
void set_armature (const VectorXs &armature)
 
void set_damping_factor (const Scalar &damping)
 
void set_restitution_coefficient (const Scalar &r_coeff)
 
- Public Member Functions inherited from ActionModelAbstractTpl< _Scalar >
 ActionModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t &nu, const std::size_t &nr=0)
 Initialize the action model. More...
 
void calc (const boost::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
void calcDiff (const boost::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
bool const & get_has_control_limits () const
 Indicates if there are defined control limits.
 
const std::size_t & get_nr () const
 Return the dimension of the cost-residual vector.
 
const std::size_t & get_nu () const
 Return the dimension of the control input.
 
const boost::shared_ptr< StateAbstract > & get_state () const
 Return the state.
 
const VectorXs & get_u_lb () const
 Return the control lower bound.
 
const VectorXs & get_u_ub () const
 Return the control upper bound.
 
virtual void quasiStatic (const boost::shared_ptr< ActionDataAbstract > &data, Eigen::Ref< VectorXs > u, const Eigen::Ref< const VectorXs > &x, const std::size_t &maxiter=100, const Scalar &tol=Scalar(1e-9))
 Computes the quasic static commands. More...
 
VectorXs quasiStatic_x (const boost::shared_ptr< ActionDataAbstract > &data, const VectorXs &x, const std::size_t &maxiter=100, const Scalar &tol=Scalar(1e-9))
 
void set_u_lb (const VectorXs &u_lb)
 Modify the control lower bounds.
 
void set_u_ub (const VectorXs &u_ub)
 Modify the control upper bounds.
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 
- Public Attributes inherited from ActionModelAbstractTpl< _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Additional Inherited Members

- Protected Member Functions inherited from ActionModelAbstractTpl< _Scalar >
void update_has_control_limits ()
 Update the status of the control limits (i.e. if there are defined limits)
 
- Protected Attributes inherited from ActionModelAbstractTpl< _Scalar >
bool has_control_limits_
 Indicates whether any of the control limits is finite.
 
std::size_t nr_
 Dimension of the cost residual.
 
std::size_t nu_
 Control dimension.
 
boost::shared_ptr< StateAbstractstate_
 Model of the state.
 
VectorXs u_lb_
 Lower control limits.
 
VectorXs u_ub_
 Upper control limits.
 
VectorXs unone_
 Neutral state.
 

Detailed Description

template<typename _Scalar>
class crocoddyl::ActionModelImpulseFwdDynamicsTpl< _Scalar >

Definition at line 34 of file impulse-fwddyn.hpp.

Member Function Documentation

◆ calc()

virtual void calc ( const boost::shared_ptr< ActionDataAbstract > &  data,
const Eigen::Ref< const VectorXs > &  x,
const Eigen::Ref< const VectorXs > &  u 
)
virtual

Compute the next state and cost value.

Parameters
[in]dataAction data
[in]xState point
[in]uControl input

Implements ActionModelAbstractTpl< _Scalar >.

◆ calcDiff()

virtual void calcDiff ( const boost::shared_ptr< ActionDataAbstract > &  data,
const Eigen::Ref< const VectorXs > &  x,
const Eigen::Ref< const VectorXs > &  u 
)
virtual

Compute the derivatives of the dynamics and cost functions.

It computes the partial derivatives of the dynamical system and the cost function. It assumes that calc() has been run first. This function builds a linear-quadratic approximation of the action model (i.e. dynamical system and cost function).

Parameters
[in]dataAction data
[in]xState point
[in]uControl input

Implements ActionModelAbstractTpl< _Scalar >.

◆ createData()

virtual boost::shared_ptr<ActionDataAbstract> createData ( )
virtual

Create the action data.

Returns
the action data

Reimplemented from ActionModelAbstractTpl< _Scalar >.


The documentation for this class was generated from the following file: