crocoddyl  1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
ResidualModelContactWrenchConeTpl< _Scalar > Class Template Reference

Contact wrench cone residual function. More...

#include <crocoddyl/multibody/residuals/contact-wrench-cone.hpp>

Public Types

typedef ResidualModelAbstractTpl< Scalar > Base
 
typedef ResidualDataContactWrenchConeTpl< Scalar > Data
 
typedef DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixX6s MatrixX6s
 
typedef MathBase::MatrixXs MatrixXs
 
typedef ResidualDataAbstractTpl< Scalar > ResidualDataAbstract
 
typedef StateMultibodyTpl< Scalar > StateMultibody
 
typedef MathBase::VectorXs VectorXs
 
typedef WrenchConeTpl< Scalar > WrenchCone
 

Public Member Functions

 ResidualModelContactWrenchConeTpl (boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const WrenchCone &fref)
 Initialize the contact wrench cone residual model. More...
 
 ResidualModelContactWrenchConeTpl (boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const WrenchCone &fref, const std::size_t nu)
 Initialize the contact wrench cone 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 wrench cone 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 wrench cone residual. More...
 
virtual boost::shared_ptr< ResidualDataAbstractcreateData (DataCollectorAbstract *const data)
 Create the contact wrench cone residual data. More...
 
pinocchio::FrameIndex get_id () const
 Return the reference frame id.
 
const WrenchConeget_reference () const
 Return the reference contact wrench cone.
 
virtual void print (std::ostream &os) const
 Print relevant information of the contact-wrench-cone residual. More...
 
void set_id (const pinocchio::FrameIndex id)
 Modify the reference frame id.
 
void set_reference (const WrenchCone &reference)
 Modify the reference contact wrench cone.
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Protected Attributes

std::size_t nu_
 Control dimension.
 
boost::shared_ptr< StateAbstractstate_
 State description.
 
VectorXs unone_
 No control vector.
 

Detailed Description

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

Contact wrench cone residual function.

This residual function is defined as \(\mathbf{r}=\mathbf{A}\boldsymbol{\lambda}\), where \(\mathbf{A}\) is the inequality matrix defined by the contact wrench cone, and \(\boldsymbol{\lambda}\) is the current spatial forces. 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, DataCollectorForceTpl

Definition at line 117 of file fwd.hpp.

Constructor & Destructor Documentation

◆ ResidualModelContactWrenchConeTpl() [1/2]

ResidualModelContactWrenchConeTpl ( boost::shared_ptr< StateMultibody state,
const pinocchio::FrameIndex  id,
const WrenchCone fref,
const std::size_t  nu 
)

Initialize the contact wrench cone residual model.

Parameters
[in]stateMultibody state
[in]idReference frame id
[in]frefReference contact wrench cone
[in]nuDimension of control vector

◆ ResidualModelContactWrenchConeTpl() [2/2]

ResidualModelContactWrenchConeTpl ( boost::shared_ptr< StateMultibody state,
const pinocchio::FrameIndex  id,
const WrenchCone fref 
)

Initialize the contact wrench cone residual model.

The default nu is obtained from StateAbstractTpl::get_nv().

Parameters
[in]stateMultibody state
[in]idReference frame id
[in]frefReference contact wrench cone

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 wrench cone 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}\)

◆ 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}\)

◆ 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 wrench cone 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}\)

◆ 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}\)

◆ createData()

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

Create the contact wrench cone residual data.

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

◆ print()

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

Print relevant information of the contact-wrench-cone residual.

Parameters
[out]osOutput stream object

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