Crocoddyl
DifferentialActionModelFreeFwdDynamicsTpl< _Scalar > Class Template Reference

Differential action model for free forward dynamics in multibody systems. More...

#include <free-fwddyn.hpp>

Inheritance diagram for DifferentialActionModelFreeFwdDynamicsTpl< _Scalar >:
DifferentialActionModelAbstractTpl< _Scalar >

Public Types

typedef ActuationModelAbstractTpl< Scalar > ActuationModelAbstract
 
typedef DifferentialActionModelAbstractTpl< Scalar > Base
 
typedef ConstraintModelManagerTpl< Scalar > ConstraintModelManager
 
typedef CostModelSumTpl< Scalar > CostModelSum
 
typedef DifferentialActionDataFreeFwdDynamicsTpl< Scalar > Data
 
typedef DifferentialActionDataAbstractTpl< Scalar > DifferentialActionDataAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef StateMultibodyTpl< Scalar > StateMultibody
 
typedef MathBase::VectorXs VectorXs
 
- Public Types inherited from DifferentialActionModelAbstractTpl< _Scalar >
typedef DifferentialActionDataAbstractTpl< Scalar > DifferentialActionDataAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 DifferentialActionModelFreeFwdDynamicsTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActuationModelAbstract > actuation, boost::shared_ptr< CostModelSum > costs, boost::shared_ptr< ConstraintModelManager > constraints=nullptr)
 
virtual void calc (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
virtual void calc (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the system acceleration, and cost value. More...
 
virtual void calcDiff (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
virtual void calcDiff (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the derivatives of the contact dynamics, and cost function. More...
 
virtual bool checkData (const boost::shared_ptr< DifferentialActionDataAbstract > &data)
 Check that the given data belongs to the free forward-dynamics data.
 
virtual boost::shared_ptr< DifferentialActionDataAbstractcreateData ()
 Create the free forward-dynamics data. More...
 
const boost::shared_ptr< ActuationModelAbstract > & get_actuation () const
 Return the actuation model.
 
const VectorXs & get_armature () const
 Return the armature vector.
 
const boost::shared_ptr< ConstraintModelManager > & get_constraints () const
 Return the constraint model manager.
 
const boost::shared_ptr< CostModelSum > & get_costs () const
 Return the cost model.
 
virtual const VectorXs & get_g_lb () const
 Return the lower bound of the inequality constraints.
 
virtual const VectorXs & get_g_ub () const
 Return the upper bound of the inequality constraints.
 
virtual std::size_t get_ng () const
 Return the number of inequality constraints.
 
virtual std::size_t get_nh () const
 Return the number of equality constraints.
 
pinocchio::ModelTpl< Scalar > & get_pinocchio () const
 Return the Pinocchio model.
 
virtual void print (std::ostream &os) const
 Print relevant information of the free forward-dynamics model. More...
 
virtual void quasiStatic (const boost::shared_ptr< DifferentialActionDataAbstract > &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...
 
void set_armature (const VectorXs &armature)
 Modify the armature vector.
 
- Public Member Functions inherited from DifferentialActionModelAbstractTpl< _Scalar >
 DifferentialActionModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nu, const std::size_t nr=0, const std::size_t ng=0, const std::size_t nh=0)
 Initialize the differential action model. More...
 
bool get_has_control_limits () const
 Indicates if there are defined control limits.
 
std::size_t get_nr () const
 Return the dimension of the cost-residual vector.
 
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.
 
VectorXs quasiStatic_x (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const VectorXs &x, const std::size_t maxiter=100, const Scalar tol=Scalar(1e-9))
 
void set_g_lb (const VectorXs &g_lb)
 Modify the lower bound of the inequality constraints.
 
void set_g_ub (const VectorXs &g_ub)
 Modify the upper bound of the inequality constraints.
 
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 DifferentialActionModelAbstractTpl< _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Protected Attributes

VectorXs g_lb_
 Lower bound of the inequality constraints.
 
VectorXs g_ub_
 < Lower bound of the inequality constraints
 
std::size_t nu_
 < Upper bound of the inequality constraints
 
boost::shared_ptr< StateAbstractstate_
 < Control dimension
 
- Protected Attributes inherited from DifferentialActionModelAbstractTpl< _Scalar >
VectorXs g_lb_
 Lower bound of the inequality constraints.
 
VectorXs g_ub_
 Lower bound of the inequality constraints.
 
bool has_control_limits_
 
std::size_t ng_
 Number of inequality constraints.
 
std::size_t nh_
 Number of equality constraints.
 
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.
 

Additional Inherited Members

- Protected Member Functions inherited from DifferentialActionModelAbstractTpl< _Scalar >
void update_has_control_limits ()
 Update the status of the control limits (i.e. if there are defined limits)
 

Detailed Description

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

Differential action model for free forward dynamics in multibody systems.

This class implements free forward dynamics, i.e.,

\[ \mathbf{M}\dot{\mathbf{v}} + \mathbf{h}(\mathbf{q},\mathbf{v}) = \boldsymbol{\tau}, \]

where \(\mathbf{q}\in Q\), \(\mathbf{v}\in\mathbb{R}^{nv}\) are the configuration point and generalized velocity (its tangent vector), respectively; \(\boldsymbol{\tau}\) is the torque inputs and \(\mathbf{h}(\mathbf{q},\mathbf{v})\) are the Coriolis effect and gravity field.

The derivatives of the system acceleration is computed efficiently based on the analytical derivatives of Articulate Body Algorithm (ABA) as described in [carpentier-rss18].

The stack of cost functions is implemented in CostModelSumTpl. The computation of the free forward dynamics and its derivatives are carrying out inside calc() and calcDiff() functions, respectively. It is also important to remark that calcDiff() computes the derivatives using the latest stored values by calc(). Thus, we need to run calc() first.

See also
DifferentialActionModelAbstractTpl, calc(), calcDiff(), createData()

Definition at line 59 of file free-fwddyn.hpp.

Member Function Documentation

◆ calc() [1/2]

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

Compute the system acceleration, and cost value.

It computes the system acceleration using the free forward-dynamics.

Parameters
[in]dataFree forward-dynamics data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Implements DifferentialActionModelAbstractTpl< _Scalar >.

◆ calc() [2/2]

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

◆ calcDiff() [1/2]

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

Compute the derivatives of the contact dynamics, and cost function.

Parameters
[in]dataFree forward-dynamics data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Implements DifferentialActionModelAbstractTpl< _Scalar >.

◆ calcDiff() [2/2]

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

◆ createData()

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

Create the free forward-dynamics data.

Returns
free forward-dynamics data

Reimplemented from DifferentialActionModelAbstractTpl< _Scalar >.

◆ quasiStatic()

virtual void quasiStatic ( const boost::shared_ptr< DifferentialActionDataAbstract > &  data,
Eigen::Ref< VectorXs >  u,
const Eigen::Ref< const VectorXs > &  x,
const std::size_t  maxiter = 100,
const Scalar  tol = Scalar(1e-9) 
)
virtual

Computes the quasic static commands.

The quasic static commands are the ones produced for a the reference posture as an equilibrium point, i.e. for \(\mathbf{f}(\mathbf{q},\mathbf{v}=\mathbf{0},\mathbf{u})=\mathbf{0}\)

Parameters
[in]dataDifferential action data
[out]uQuasic static commands
[in]xState point (velocity has to be zero)
[in]maxiterMaximum allowed number of iterations
[in]tolTolerance

Reimplemented from DifferentialActionModelAbstractTpl< _Scalar >.

◆ print()

virtual void print ( std::ostream &  os) const
virtual

Print relevant information of the free forward-dynamics model.

Parameters
[out]osOutput stream object

Reimplemented from DifferentialActionModelAbstractTpl< _Scalar >.


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