crocoddyl 1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
 
Loading...
Searching...
No Matches
ResidualModelContactFrictionConeTpl< _Scalar > Class Template Reference

Contact friction cone residual. More...

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

Inheritance diagram for ResidualModelContactFrictionConeTpl< _Scalar >:
Collaboration diagram for ResidualModelContactFrictionConeTpl< _Scalar >:

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 DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
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)
 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< ResidualDataAbstractcreateData (DataCollectorAbstract *const data)
 Create the contact friction cone residual data. More...
 
pinocchio::FrameIndex get_id () const
 Return the reference frame id.
 
const FrictionConeget_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 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)
 
 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 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 residual vector. 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 Jacobian of the residual vector. More...
 
virtual boost::shared_ptr< ResidualDataAbstractcreateData (DataCollectorAbstract *const data)
 Create the residual data. 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.
 
virtual void print (std::ostream &os) const
 Print relevant information of the residual model. More...
 

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. More...
 
boost::shared_ptr< StateAbstractstate_
 State description. More...
 
VectorXs unone_
 No control vector. More...
 
- Protected Attributes inherited from ResidualModelAbstractTpl< _Scalar >
std::size_t nr_
 Residual vector dimension. More...
 
std::size_t nu_
 Control dimension. More...
 
bool q_dependent_
 Label that indicates if the residual function depends on q. More...
 
boost::shared_ptr< StateAbstractstate_
 State description. More...
 
bool u_dependent_
 Label that indicates if the residual function depends on u. More...
 
VectorXs unone_
 No control vector. More...
 
bool v_dependent_
 Label that indicates if the residual function depends on v. More...
 

Detailed Description

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

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.

See also
ResidualModelAbstractTpl, calc(), calcDiff(), createData(), DifferentialActionModelContactFwdDynamicsTpl, ActionModelImpulseFwdDynamicTpl, DataCollectorForceTpl

Definition at line 54 of file contact-friction-cone.hpp.

Member Typedef Documentation

◆ MathBase

typedef MathBaseTpl<Scalar> MathBase

Definition at line 59 of file contact-friction-cone.hpp.

◆ Base

typedef ResidualModelAbstractTpl<Scalar> Base

Definition at line 60 of file contact-friction-cone.hpp.

◆ Data

Definition at line 61 of file contact-friction-cone.hpp.

◆ StateMultibody

Definition at line 62 of file contact-friction-cone.hpp.

◆ ResidualDataAbstract

Definition at line 63 of file contact-friction-cone.hpp.

◆ DataCollectorAbstract

Definition at line 64 of file contact-friction-cone.hpp.

◆ FrictionCone

typedef FrictionConeTpl<Scalar> FrictionCone

Definition at line 65 of file contact-friction-cone.hpp.

◆ VectorXs

typedef MathBase::VectorXs VectorXs

Definition at line 66 of file contact-friction-cone.hpp.

◆ MatrixXs

typedef MathBase::MatrixXs MatrixXs

Definition at line 67 of file contact-friction-cone.hpp.

◆ MatrixX3s

typedef MathBase::MatrixX3s MatrixX3s

Definition at line 68 of file contact-friction-cone.hpp.

Constructor & Destructor Documentation

◆ ResidualModelContactFrictionConeTpl() [1/2]

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.

Parameters
[in]stateState of the multibody system
[in]idReference frame id
[in]frefReference friction cone
[in]nuDimension of the control vector

◆ ResidualModelContactFrictionConeTpl() [2/2]

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().

Parameters
[in]stateState of the multibody system
[in]idReference frame id
[in]frefReference friction 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 friction cone residual.

Parameters
[in]dataContact friction cone residual 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 Jacobians of the contact friction cone residual.

Parameters
[in]dataContact friction cone residual 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 friction cone residual data.

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

◆ print()

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

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

Parameters
[out]osOutput stream object

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

Member Data Documentation

◆ Scalar

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar

Definition at line 58 of file contact-friction-cone.hpp.

◆ nu_

std::size_t nu_
protected

Control dimension.

Definition at line 181 of file residual-base.hpp.

◆ state_

boost::shared_ptr<StateAbstract> state_
protected

State description.

Definition at line 179 of file residual-base.hpp.

◆ unone_

VectorXs unone_
protected

No control vector.

Definition at line 182 of file residual-base.hpp.


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