Contact friction cone residual. More...
#include <crocoddyl/multibody/residuals/contact-friction-cone.hpp>
Public Types | |
typedef ResidualModelAbstractTpl< Scalar > | Base |
typedef ResidualDataContactFrictionConeTpl< Scalar > | Data |
typedef DataCollectorAbstractTpl< Scalar > | DataCollectorAbstract |
typedef FrictionConeTpl< Scalar > | FrictionCone |
typedef MathBaseTpl< Scalar > | MathBase |
typedef MathBase::MatrixX3s | MatrixX3s |
typedef MathBase::MatrixXs | MatrixXs |
typedef ResidualDataAbstractTpl< Scalar > | ResidualDataAbstract |
typedef StateMultibodyTpl< Scalar > | StateMultibody |
typedef MathBase::VectorXs | VectorXs |
Public Member Functions | |
ResidualModelContactFrictionConeTpl (boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const FrictionCone &fref) | |
Initialize the contact friction cone residual model. More... | |
ResidualModelContactFrictionConeTpl (boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const FrictionCone &fref, const std::size_t nu) | |
Initialize the contact friction cone residual model. 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 friction cone residual. More... | |
virtual void | calcDiff (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) |
Compute the Jacobians of the contact friction cone residual. More... | |
virtual boost::shared_ptr< ResidualDataAbstract > | createData (DataCollectorAbstract *const data) |
Create the contact friction cone residual data. | |
pinocchio::FrameIndex | get_id () const |
Return the reference frame id. | |
const FrictionCone & | get_reference () const |
Return the reference contact friction cone. | |
virtual void | print (std::ostream &os) const |
Print relevant information of the contact-friction-cone residual. More... | |
void | set_id (const pinocchio::FrameIndex id) |
Modify the reference frame id. | |
void | set_reference (const FrictionCone &reference) |
Modify the reference contact friction cone. | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
Protected Attributes | |
std::size_t | nu_ |
Control dimension. | |
boost::shared_ptr< StateAbstract > | state_ |
State description. | |
VectorXs | unone_ |
No control vector. | |
Contact friction cone residual.
This residual function is defined as \(\mathbf{r}=\mathbf{A}\boldsymbol{\lambda}\), where \(\mathbf{A}\in~\mathbb{R}^{nr\times nc}\) describes the linearized friction cone, \(\boldsymbol{\lambda}\in~\mathbb{R}^{nc}\) is the spatial contact forces computed by DifferentialActionModelContactFwdDynamicsTpl
, and nr
, nc
are the number of cone facets and dimension of the contact, respectively.
Both residual and residual Jacobians are computed analytically, where th 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.
As described in ResidualModelAbstractTpl()
, the residual value and its derivatives are calculated by calc
and calcDiff
, respectively.
ResidualModelAbstractTpl
, calc()
, calcDiff()
, createData()
, DifferentialActionModelContactFwdDynamicsTpl
, ActionModelImpulseFwdDynamicTpl
, DataCollectorForceTpl
ResidualModelContactFrictionConeTpl | ( | boost::shared_ptr< StateMultibody > | state, |
const pinocchio::FrameIndex | id, | ||
const FrictionCone & | fref, | ||
const std::size_t | nu | ||
) |
Initialize the contact friction cone residual model.
[in] | state | State of the multibody system |
[in] | id | Reference frame id |
[in] | fref | Reference friction cone |
[in] | nu | Dimension of the control vector |
ResidualModelContactFrictionConeTpl | ( | boost::shared_ptr< StateMultibody > | state, |
const pinocchio::FrameIndex | id, | ||
const FrictionCone & | fref | ||
) |
Initialize the contact friction cone residual model.
The default nu
value is obtained from StateAbstractTpl::get_nv()
.
[in] | state | State of the multibody system |
[in] | id | Reference frame id |
[in] | fref | Reference friction cone |
|
virtual |
Compute the contact friction cone residual.
[in] | data | Contact friction cone residual data |
[in] | x | State point \(\mathbf{x}\in\mathbb{R}^{ndx}\) |
[in] | u | Control input \(\mathbf{u}\in\mathbb{R}^{nu}\) |
|
virtual |
Compute the Jacobians of the contact friction cone residual.
[in] | data | Contact friction cone residual data |
[in] | x | State point \(\mathbf{x}\in\mathbb{R}^{ndx}\) |
[in] | u | Control input \(\mathbf{u}\in\mathbb{R}^{nu}\) |
|
virtual |
Print relevant information of the contact-friction-cone residual.
[out] | os | Output stream object |