Template Class ResidualModelContactCoPPositionTpl

Inheritance Relationships

Base Type

Class Documentation

template<typename _Scalar>
class ResidualModelContactCoPPositionTpl : public crocoddyl::ResidualModelAbstractTpl<_Scalar>

Center of pressure residual function.

It builds a residual function that bounds the center of pressure (CoP) for one contact surface to lie inside a certain geometric area defined around the reference contact frame. The residual residual vector is described as \(\mathbf{r}=\mathbf{A}\boldsymbol{\lambda}\geq\mathbf{0}\), where

\[\begin{split} \mathbf{A}= \begin{bmatrix} 0 & 0 & X/2 & 0 & -1 & 0 \\ 0 & 0 & X/2 & 0 & 1 & 0 \\ 0 & 0 & Y/2 & 1 & 0 & 0 \\ 0 & 0 & Y/2 & -1 & 0 & 0 \end{bmatrix} \end{split}\]
is the inequality matrix and \(\boldsymbol{\lambda}\) is the reference spatial contact force in the frame coordinate. The CoP lies inside the convex hull of the foot, see eq.(18-19) of https://hal.archives-ouvertes.fr/hal-02108449/document is we have:
\[\begin{split} \begin{align}\begin{split}\tau^x &\leq Yf^z \\-\tau^x &\leq Yf^z \\\tau^y &\leq Yf^z \\-\tau^y &\leq Yf^z \end{split}\end{align} \end{split}\]
with \(\boldsymbol{\lambda}= \begin{bmatrix}f^x & f^y & f^z & \tau^x & \tau^y & \tau^z \end{bmatrix}^T\).

The residual is computed, from the residual vector \(\mathbf{r}\), through an user defined activation model. Additionally, the contact frame id, the desired support region for the CoP and the inequality matrix are handled within CoPSupportTpl. The force vector \(\boldsymbol{\lambda}\) and its derivatives 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.

Public Types

typedef MathBaseTpl<Scalar> MathBase
typedef ResidualModelAbstractTpl<Scalar> Base
typedef ResidualDataContactCoPPositionTpl<Scalar> Data
typedef StateMultibodyTpl<Scalar> StateMultibody
typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract
typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract
typedef CoPSupportTpl<Scalar> CoPSupport
typedef MathBase::VectorXs VectorXs
typedef MathBase::MatrixXs MatrixXs
typedef MathBase::Matrix46s Matrix46

Public Functions

ResidualModelContactCoPPositionTpl(std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id, const CoPSupport &cref, const std::size_t nu, const bool fwddyn = true)

Initialize the contact CoP residual model.

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

Parameters:
  • state[in] State of the multibody system

  • id[in] Reference frame id

  • cref[in] Reference support region of the CoP

  • nu[in] Dimension of control vector

  • fwddyn[in] Indicates that we have a forward dynamics problem (true) or inverse dynamics (false)

ResidualModelContactCoPPositionTpl(std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id, const CoPSupport &cref)

Initialize the contact CoP residual model.

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

Parameters:
  • state[in] State of the multibody system

  • id[in] Reference frame id

  • cref[in] Reference support region of the CoP

virtual ~ResidualModelContactCoPPositionTpl() = default
virtual void calc(const std::shared_ptr<ResidualDataAbstract> &data, const Eigen::Ref<const VectorXs> &x, const Eigen::Ref<const VectorXs> &u) override

Compute the contact CoP 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:
  • data[in] Contact CoP data

  • x[in] State point \(\mathbf{x}\in\mathbb{R}^{ndx}\)

  • u[in] Control input \(\mathbf{u}\in\mathbb{R}^{nu}\)

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

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:
  • data[in] Residual data

  • x[in] State point \(\mathbf{x}\in\mathbb{R}^{ndx}\)

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

Compute the Jacobians of the contact CoP 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:
  • data[in] Contact CoP data

  • x[in] State point \(\mathbf{x}\in\mathbb{R}^{ndx}\)

  • u[in] Control input \(\mathbf{u}\in\mathbb{R}^{nu}\)

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

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:
  • data[in] Residual data

  • x[in] State point \(\mathbf{x}\in\mathbb{R}^{ndx}\)

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

Create the contact CoP residual data.

Each residual model has its own data that needs to be allocated. This function returns the allocated data for a predefined residual.

Parameters:

data[in] Shared data (it should be of type DataCollectorContactTpl)

Returns:

the residual data.

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

Update the Jacobians of the contact friction cone residual.

Parameters:

data[in] Contact friction cone residual data

template<typename NewScalar>
ResidualModelContactCoPPositionTpl<NewScalar> cast() const

Cast the contact-cop-position residual model to a different scalar type.

It is useful for operations requiring different precision or scalar types.

Template Parameters:

NewScalar – The new scalar type to cast to.

Returns:

ResidualModelContactCoPPositionTpl<NewScalar> A residual model with the new scalar type.

bool is_fwddyn() const

Indicates if we are using the forward-dynamics (true) or inverse-dynamics (false)

pinocchio::FrameIndex get_id() const

Return the reference frame id.

const CoPSupport &get_reference() const

Return the reference support region of CoP.

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

Modify the reference frame id.

Modify the reference support region of CoP

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

Print relevant information of the cop-position residual.

Parameters:

os[out] Output stream object

Public Members

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar

Protected Attributes

std::size_t nu_

Control dimension.

std::shared_ptr<StateAbstract> state_

State description.