Crocoddyl
ResidualModelContactForceTpl< _Scalar > Class Template Reference

Define a contact force residual function. More...

#include <contact-force.hpp>

Inheritance diagram for ResidualModelContactForceTpl< _Scalar >:
ResidualModelAbstractTpl< _Scalar >

Public Types

typedef ResidualModelAbstractTpl< Scalar > Base
 
typedef ResidualDataContactForceTpl< Scalar > Data
 
typedef DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
typedef pinocchio::ForceTpl< Scalar > Force
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef ResidualDataAbstractTpl< Scalar > ResidualDataAbstract
 
typedef StateMultibodyTpl< Scalar > StateMultibody
 
typedef MathBase::VectorXs VectorXs
 
- Public Types inherited from ResidualModelAbstractTpl< _Scalar >
typedef ActivationDataAbstractTpl< Scalar > ActivationDataAbstract
 
typedef CostDataAbstractTpl< Scalar > CostDataAbstract
 
typedef DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
typedef MathBase::DiagonalMatrixXs DiagonalMatrixXs
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef ResidualDataAbstractTpl< Scalar > ResidualDataAbstract
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 ResidualModelContactForceTpl (boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Force &fref, const std::size_t nc)
 Initialize the contact force residual model. More...
 
 ResidualModelContactForceTpl (boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Force &fref, const std::size_t nc, const std::size_t nu, const bool fwddyn=true)
 Initialize the contact force residual model. More...
 
virtual void calc (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Compute the residual vector for nodes that depends only on the state. More...
 
virtual void calc (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the contact force residual. More...
 
virtual void calcDiff (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Compute the Jacobian of the residual functions with respect to the state only. More...
 
virtual void calcDiff (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the derivatives of the contact force residual. More...
 
virtual boost::shared_ptr< ResidualDataAbstractcreateData (DataCollectorAbstract *const data)
 Create the contact force residual data. More...
 
 DEPRECATED ("Do not use set_id, instead create a new model", void set_id(const pinocchio::FrameIndex id);) void set_reference(const Force &reference)
 Modify the reference frame id. More...
 
pinocchio::FrameIndex get_id () const
 Return the reference frame id.
 
const Force & get_reference () const
 Return the reference spatial contact force in the contact coordinates.
 
bool is_fwddyn () const
 Indicates if we are using the forward-dynamics (true) or inverse-dynamics (false)
 
virtual void print (std::ostream &os) const
 Print relevant information of the contact-force residual. More...
 
void updateJacobians (const boost::shared_ptr< ResidualDataAbstract > &data)
 Update the Jacobians of the contact friction cone residual. More...
 
- Public Member Functions inherited from ResidualModelAbstractTpl< _Scalar >
 ResidualModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nr, const bool q_dependent=true, const bool v_dependent=true, const bool u_dependent=true)
 Initialize the residual model. More...
 
 ResidualModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nr, const std::size_t nu, const bool q_dependent=true, const bool v_dependent=true, const bool u_dependent=true)
 Initialize the residual model. More...
 
virtual void calcCostDiff (const boost::shared_ptr< CostDataAbstract > &cdata, const boost::shared_ptr< ResidualDataAbstract > &rdata, const boost::shared_ptr< ActivationDataAbstract > &adata, const bool update_u=true)
 Compute the derivative of the cost function. More...
 
std::size_t get_nr () const
 Return the dimension of the residual vector.
 
std::size_t get_nu () const
 Return the dimension of the control input.
 
bool get_q_dependent () const
 Return true if the residual function depends on q.
 
const boost::shared_ptr< StateAbstract > & get_state () const
 Return the state.
 
bool get_u_dependent () const
 Return true if the residual function depends on u.
 
bool get_v_dependent () const
 Return true if the residual function depends on v.
 

Public Attributes

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

Protected Attributes

std::size_t nr_
 Residual vector dimension.
 
std::size_t nu_
 Control dimension.
 
boost::shared_ptr< StateAbstractstate_
 State description.
 
- Protected Attributes inherited from ResidualModelAbstractTpl< _Scalar >
std::size_t nr_
 Residual vector dimension.
 
std::size_t nu_
 Control dimension.
 
bool q_dependent_
 
boost::shared_ptr< StateAbstractstate_
 State description.
 
bool u_dependent_
 
VectorXs unone_
 No control vector.
 
bool v_dependent_
 

Detailed Description

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

Define a contact force residual function.

This residual function is defined as \(\mathbf{r}=\boldsymbol{\lambda}-\boldsymbol{\lambda}^*\), where \(\boldsymbol{\lambda}, \boldsymbol{\lambda}^*\) are the current and reference spatial forces, respectively. The current spatial forces \(\boldsymbol{\lambda}\in\mathbb{R}^{nc}\) is computed by DifferentialActionModelContactFwdDynamicsTpl or ActionModelImpulseFwdDynamicTpl, with nc as the dimension of the contact.

Both residual and residual Jacobians are computed analytically, where the force vector \(\boldsymbol{\lambda}\) and its Jacobians \(\left(\frac{\partial\boldsymbol{\lambda}}{\partial\mathbf{x}}, \frac{\partial\boldsymbol{\lambda}}{\partial\mathbf{u}}\right)\) are computed by DifferentialActionModelContactFwdDynamicsTpl or ActionModelImpulseFwdDynamicTpl. These values are stored in a shared data (i.e., DataCollectorContactTpl or DataCollectorImpulseTpl). Note that this residual function cannot be used with other action models.

See also
ResidualModelAbstractTpl, calc(), calcDiff(), createData(), DifferentialActionModelContactFwdDynamicsTpl, ActionModelImpulseFwdDynamicTpl, DataCollectorContactTpl, DataCollectorImpulseTpl

Definition at line 57 of file contact-force.hpp.

Constructor & Destructor Documentation

◆ ResidualModelContactForceTpl() [1/2]

ResidualModelContactForceTpl ( boost::shared_ptr< StateMultibody state,
const pinocchio::FrameIndex  id,
const Force &  fref,
const std::size_t  nc,
const std::size_t  nu,
const bool  fwddyn = true 
)

Initialize the contact force residual model.

Note that for the inverse-dynamic cases, the control vector contains the generalized accelerations, torques, and all the contact forces.

Parameters
[in]stateMultibody state
[in]idReference frame id
[in]frefReference spatial contact force in the contact coordinates
[in]ncDimension of the contact force (nc <= 6)
[in]nuDimension of control vector
[in]fwddynIndicates that we have a forward dynamics problem (true) or inverse dynamics (false)

◆ ResidualModelContactForceTpl() [2/2]

ResidualModelContactForceTpl ( boost::shared_ptr< StateMultibody state,
const pinocchio::FrameIndex  id,
const Force &  fref,
const std::size_t  nc 
)

Initialize the contact force residual model.

The default nu is obtained from StateAbstractTpl::get_nv(). Note that this constructor can be used for forward-dynamics cases only.

Parameters
[in]stateMultibody state
[in]idReference frame id
[in]frefReference spatial contact force in the contact coordinates
[in]ncDimension of the contact force (nc <= 6)

Member Function Documentation

◆ calc() [1/2]

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

Compute the contact force residual.

The CoP residual is computed based on the \(\mathbf{A}\) matrix, the force vector is computed by DifferentialActionModelContactFwdDynamicsTpl or ActionModelImpulseFwdDynamicTpl which is stored in DataCollectorContactTpl or DataCollectorImpulseTpl.

Parameters
[in]dataContact force data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

◆ calc() [2/2]

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

Compute the residual vector for nodes that depends only on the state.

It updates the residual vector based on the state only (i.e., it ignores the contact forces). This function is used in the terminal nodes of an optimal control problem.

Parameters
[in]dataResidual data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

◆ calcDiff() [1/2]

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

Compute the derivatives of the contact force residual.

The CoP residual is computed based on the \(\mathbf{A}\) matrix, the force vector is computed by DifferentialActionModelContactFwdDynamicsTpl or ActionModelImpulseFwdDynamicTpl which is stored in DataCollectorContactTpl or DataCollectorImpulseTpl.

Parameters
[in]dataContact force data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

◆ calcDiff() [2/2]

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

Compute the Jacobian of the residual functions with respect to the state only.

It updates the Jacobian of the residual function based on the state only (i.e., it ignores the contact forces). This function is used in the terminal nodes of an optimal control problem.

Parameters
[in]dataResidual data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

◆ createData()

virtual boost::shared_ptr<ResidualDataAbstract> createData ( DataCollectorAbstract *const  data)
virtual

Create the contact force residual data.

Parameters
[in]datashared data (it should be of type DataCollectorContactTpl)
Returns
the residual data.

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

◆ updateJacobians()

void updateJacobians ( const boost::shared_ptr< ResidualDataAbstract > &  data)

Update the Jacobians of the contact friction cone residual.

Parameters
[in]dataContact friction cone residual data

◆ DEPRECATED()

DEPRECATED ( "Do not use  set_id,
instead create a new model"  ,
void set_id(const pinocchio::FrameIndex id);   
) const &

Modify the reference frame id.

Modify the reference spatial contact force in the contact coordinates

◆ print()

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

Print relevant information of the contact-force residual.

Parameters
[out]osOutput stream object

Reimplemented from ResidualModelAbstractTpl< _Scalar >.


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