Template Class ResidualModelFrameTranslationTpl

Inheritance Relationships

Base Type

Class Documentation

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

Frame translation residual.

This residual function defines the tracking of a frame translation as \(\mathbf{r}=\mathbf{t}-\mathbf{t}^*\), where \(\mathbf{t},\mathbf{t}^*\in~\mathbb{R}^3\) are the current and reference frame translations, respectively. Note that the dimension of the residual vector is 3. Furthermore, the Jacobians of the residual function are computed analytically.

As described in ResidualModelAbstractTpl(), the residual value and its Jacobians are calculated by calc and calcDiff, respectively.

Public Types

typedef MathBaseTpl<Scalar> MathBase
typedef ResidualModelAbstractTpl<Scalar> Base
typedef ResidualDataFrameTranslationTpl<Scalar> Data
typedef StateMultibodyTpl<Scalar> StateMultibody
typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract
typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract
typedef MathBase::VectorXs VectorXs
typedef MathBase::Vector3s Vector3s

Public Functions

ResidualModelFrameTranslationTpl(std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id, const Vector3s &xref, const std::size_t nu)

Initialize the frame translation residual model.

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

  • id[in] Reference frame id

  • xref[in] Reference frame translation

  • nu[in] Dimension of the control vector

ResidualModelFrameTranslationTpl(std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id, const Vector3s &xref)

Initialize the frame translation residual model.

The default nu is equals to StateAbstractTpl::get_nv().

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

  • id[in] Reference frame id

  • xref[in] Reference frame translation

virtual ~ResidualModelFrameTranslationTpl() = 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 frame translation residual.

Parameters:
  • data[in] Frame translation residual 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, const Eigen::Ref<const VectorXs> &u) override

Compute the derivatives of the frame translation residual.

Parameters:
  • data[in] Frame translation residual data

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

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

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

Create the frame translation residual data.

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

Cast the frame-translation 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:

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

pinocchio::FrameIndex get_id() const

Return the reference frame id.

const Vector3s &get_reference() const

Return the reference frame translation.

void set_id(const pinocchio::FrameIndex id)

Modify the reference frame id.

void set_reference(const Vector3s &reference)

Modify the reference frame translation reference.

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

Print relevant information of the frame-translation 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.

bool u_dependent_

Label that indicates if the residual function depends on u

bool v_dependent_

Label that indicates if the residual function depends on v