Template Class ResidualModelFrameVelocityTpl

Inheritance Relationships

Base Type

Class Documentation

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

Frame velocity residual.

This residual function defines a tracking of frame velocity as \(\mathbf{r}=\mathbf{v}-\mathbf{v}^*\), where \(\mathbf{v},\mathbf{v}^*\in~T_{\mathbf{p}}~\mathbb{SE(3)}\) are the current and reference frame velocities, respectively. Note that the tangent vector is described by the frame placement \(\mathbf{p}\), and the dimension of the residual vector is 6. Furthermore, the Jacobians of the residual function are computed analytically.

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

Public Types

typedef MathBaseTpl<Scalar> MathBase
typedef ResidualModelAbstractTpl<Scalar> Base
typedef ResidualDataFrameVelocityTpl<Scalar> Data
typedef StateMultibodyTpl<Scalar> StateMultibody
typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract
typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract
typedef pinocchio::MotionTpl<Scalar> Motion
typedef MathBase::VectorXs VectorXs

Public Functions

ResidualModelFrameVelocityTpl(std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id, const Motion &vref, const pinocchio::ReferenceFrame type, const std::size_t nu)

Initialize the frame velocity residual model.

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

  • id[in] Reference frame id

  • vref[in] Reference velocity

  • type[in] Reference type of velocity (WORLD, LOCAL, LOCAL_WORLD_ALIGNED)

  • nu[in] Dimension of the control vector

ResidualModelFrameVelocityTpl(std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id, const Motion &vref, const pinocchio::ReferenceFrame type)

Initialize the frame velocity residual model.

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

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

  • id[in] Reference frame id

  • vref[in] Reference velocity

  • type[in] Reference type of velocity (WORLD, LOCAL, LOCAL_WORLD_ALIGNED)

virtual ~ResidualModelFrameVelocityTpl() = 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 velocity residual vector.

Parameters:
  • data[in] Frame velocity 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 Jacobians of the frame velocity residual.

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

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

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

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

pinocchio::FrameIndex get_id() const

Return the reference frame id.

const Motion &get_reference() const

Return the reference velocity.

pinocchio::ReferenceFrame get_type() const

Return the reference type of velocity.

void set_id(const pinocchio::FrameIndex id)

Modify reference frame id.

void set_reference(const Motion &velocity)

Modify reference velocity.

void set_type(const pinocchio::ReferenceFrame type)

Modify reference type of velocity.

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

Print relevant information of the frame-velocity residual.

Parameters:

os[out] Output stream object

Public Members

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar

Protected Attributes

std::size_t nr_

Residual vector dimension.

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