Template Class ResidualModelFramePlacementTpl

Inheritance Relationships

Base Type

Class Documentation

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

Frame placement residual.

This residual function defines the frame placement tracking as \(\mathbf{r}=\mathbf{p}\ominus\mathbf{p}^*\), where \(\mathbf{p},\mathbf{p}^*\in~\mathbb{SE(3)}\) are the current and reference frame placements, respectively. Note that the dimension of the residual vector is 6. 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 ResidualDataFramePlacementTpl<Scalar> Data
typedef StateMultibodyTpl<Scalar> StateMultibody
typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract
typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract
typedef MathBase::VectorXs VectorXs
typedef pinocchio::SE3Tpl<Scalar> SE3

Public Functions

ResidualModelFramePlacementTpl(std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id, const SE3 &pref, const std::size_t nu)

Initialize the frame placement residual model.

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

  • id[in] Reference frame id

  • pref[in] Reference frame placement

  • nu[in] Dimension of the control vector

ResidualModelFramePlacementTpl(std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id, const SE3 &pref)

Initialize the frame placement residual model.

The default nu is obtained from StateAbstractTpl::get_nv().

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

  • id[in] Reference frame id

  • pref[in] Reference frame placement

virtual ~ResidualModelFramePlacementTpl() = 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 placement residual.

Parameters:
  • data[in] Frame placement 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 placement residual.

Parameters:
  • data[in] Frame-placement 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 placement residual data.

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

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

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

pinocchio::FrameIndex get_id() const

Return the reference frame id.

const SE3 &get_reference() const

Return the reference frame placement.

void set_id(const pinocchio::FrameIndex id)

Modify the reference frame id.

void set_reference(const SE3 &reference)

Modify the reference frame placement.

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

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