Crocoddyl
DifferentialActionModelContactInvDynamicsTpl< _Scalar > Class Template Reference

Differential action model for contact inverse dynamics in multibody systems. More...

#include <contact-invdyn.hpp>

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

Classes

class  ResidualModelActuation
 Actuation residual. More...
 
class  ResidualModelContact
 Contact-acceleration residual. More...
 

Public Types

typedef ActuationModelAbstractTpl< Scalar > ActuationModelAbstract
 
typedef DifferentialActionModelAbstractTpl< Scalar > Base
 
typedef ConstraintModelManagerTpl< Scalar > ConstraintModelManager
 
typedef ContactItemTpl< Scalar > ContactItem
 
typedef ContactModelMultipleTpl< Scalar > ContactModelMultiple
 
typedef CostModelSumTpl< Scalar > CostModelSum
 
typedef DifferentialActionDataContactInvDynamicsTpl< Scalar > Data
 
typedef DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
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

 DifferentialActionModelContactInvDynamicsTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActuationModelAbstract > actuation, boost::shared_ptr< ContactModelMultiple > contacts, boost::shared_ptr< CostModelSum > costs)
 Initialize the contact inverse-dynamics action model. More...
 
 DifferentialActionModelContactInvDynamicsTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActuationModelAbstract > actuation, boost::shared_ptr< ContactModelMultiple > contacts, boost::shared_ptr< CostModelSum > costs, boost::shared_ptr< ConstraintModelManager > constraints)
 Initialize the contact inverse-dynamics action model. More...
 
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, cost value and constraint residuals. 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 dynamics, cost and constraint functions. More...
 
virtual bool checkData (const boost::shared_ptr< DifferentialActionDataAbstract > &data)
 Checks that a specific data belongs to the contact inverse-dynamics model.
 
virtual boost::shared_ptr< DifferentialActionDataAbstractcreateData ()
 Create the contact inverse-dynamics data. More...
 
const boost::shared_ptr< ActuationModelAbstract > & get_actuation () const
 Return the actuation model.
 
const boost::shared_ptr< ConstraintModelManager > & get_constraints () const
 Return the constraint model manager.
 
const boost::shared_ptr< ContactModelMultiple > & get_contacts () const
 Return the contact model.
 
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 contact inverse-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...
 
- 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 ng_
 < Upper bound of the inequality constraints
 
std::size_t nh_
 < Number of inequality constraints
 
std::size_t nu_
 < Number of equality 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::DifferentialActionModelContactInvDynamicsTpl< _Scalar >

Differential action model for contact inverse dynamics in multibody systems.

This class implements forward kinematic with holonomic contact constraints (defined at the acceleration level) and inverse-dynamics computation using the Recursive Newton Euler Algorithm (RNEA). The stack of cost and constraint functions are implemented in CostModelSumTpl and ConstraintModelManagerTpl, respectively. The acceleration and contact forces are decision variables defined as the control inputs, and the under-actuation and contact constraint are under the name tau and its frame name, thus the user is not allowed to use it.

Additionally, it is important to note that calcDiff() computes the derivatives using the latest stored values by calc(). Thus, we need to first run calc().

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

Definition at line 44 of file contact-invdyn.hpp.

Constructor & Destructor Documentation

◆ DifferentialActionModelContactInvDynamicsTpl() [1/2]

DifferentialActionModelContactInvDynamicsTpl ( boost::shared_ptr< StateMultibody state,
boost::shared_ptr< ActuationModelAbstract actuation,
boost::shared_ptr< ContactModelMultiple contacts,
boost::shared_ptr< CostModelSum costs 
)

Initialize the contact inverse-dynamics action model.

It describes the kinematic evolution of the multibody system with contacts, and computes the needed torques using inverse-dynamics.

Parameters
[in]stateState of the multibody system
[in]actuationActuation model
[in]contactsMultiple contacts
[in]costsCost model

◆ DifferentialActionModelContactInvDynamicsTpl() [2/2]

DifferentialActionModelContactInvDynamicsTpl ( boost::shared_ptr< StateMultibody state,
boost::shared_ptr< ActuationModelAbstract actuation,
boost::shared_ptr< ContactModelMultiple contacts,
boost::shared_ptr< CostModelSum costs,
boost::shared_ptr< ConstraintModelManager constraints 
)

Initialize the contact inverse-dynamics action model.

Parameters
[in]stateState of the multibody system
[in]actuationActuation model
[in]contactsMultiple contacts
[in]costsCost model
[in]constraintsConstraints model

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, cost value and constraint residuals.

It extracts the acceleration value from control vector and also computes the cost and constraints.

Parameters
[in]dataContact inverse-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 dynamics, cost and constraint functions.

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

Parameters
[in]dataContact inverse-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 contact inverse-dynamics data.

Returns
contact inverse-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 reference posture as an equilibrium point with zero acceleration, i.e., for \(\mathbf{f^q_x}\delta\mathbf{q}+\mathbf{f_u}\delta\mathbf{u}=\mathbf{0}\)

Parameters
[in]dataContact inverse-dynamics data
[out]uQuasic-static commands
[in]xState point (velocity has to be zero)
[in]maxiterMaximum allowed number of iterations (default 100)
[in]tolTolerance (default 1e-9)

Reimplemented from DifferentialActionModelAbstractTpl< _Scalar >.

◆ print()

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

Print relevant information of the contact inverse-dynamics model.

Parameters
[out]osOutput stream object

Reimplemented from DifferentialActionModelAbstractTpl< _Scalar >.


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