Contact friction cone residual. More...
#include <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 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 | |
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, const bool fwddyn=true) | |
Initialize the contact friction 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 friction 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 Jacobians of the contact friction cone residual. More... | |
virtual boost::shared_ptr< ResidualDataAbstract > | createData (DataCollectorAbstract *const data) |
Create the contact friction cone residual data. | |
DEPRECATED ("Do not use set_id, instead create a new model", void set_id(const pinocchio::FrameIndex id);) void set_reference(const FrictionCone &reference) | |
Modify the reference frame id. More... | |
pinocchio::FrameIndex | get_id () const |
Return the reference frame id. | |
const FrictionCone & | get_reference () const |
Return the reference contact friction cone. | |
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-friction-cone 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 | nu_ |
Control dimension. | |
boost::shared_ptr< StateAbstract > | state_ |
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< StateAbstract > | state_ |
State description. | |
bool | u_dependent_ |
VectorXs | unone_ |
No control vector. | |
bool | v_dependent_ |
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
Definition at line 60 of file contact-friction-cone.hpp.
ResidualModelContactFrictionConeTpl | ( | boost::shared_ptr< StateMultibody > | state, |
const pinocchio::FrameIndex | id, | ||
const FrictionCone & | fref, | ||
const std::size_t | nu, | ||
const bool | fwddyn = true |
||
) |
Initialize the contact friction cone residual model.
Note that for the inverse-dynamic cases, the control vector contains the generalized accelerations, torques, and all the contact forces.
[in] | state | State of the multibody system |
[in] | id | Reference frame id |
[in] | fref | Reference friction cone |
[in] | nu | Dimension of the control vector |
[in] | fwddyn | Indicates that we have a forward dynamics problem (true) or inverse dynamics (false) |
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()
. Note that this constructor can be used for forward-dynamics cases only.
[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}\) |
Reimplemented from ResidualModelAbstractTpl< _Scalar >.
|
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.
[in] | data | Residual data |
[in] | x | State point \(\mathbf{x}\in\mathbb{R}^{ndx}\) |
Reimplemented from ResidualModelAbstractTpl< _Scalar >.
|
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}\) |
Reimplemented from ResidualModelAbstractTpl< _Scalar >.
|
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.
[in] | data | Residual data |
[in] | x | State point \(\mathbf{x}\in\mathbb{R}^{ndx}\) |
Reimplemented from ResidualModelAbstractTpl< _Scalar >.
void updateJacobians | ( | const boost::shared_ptr< ResidualDataAbstract > & | data | ) |
Update the Jacobians of the contact friction cone residual.
[in] | data | Contact friction cone residual data |
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 contact friction cone
|
virtual |
Print relevant information of the contact-friction-cone residual.
[out] | os | Output stream object |
Reimplemented from ResidualModelAbstractTpl< _Scalar >.