Crocoddyl
ResidualModelFrameVelocityTpl< _Scalar > Class Template Reference

Frame velocity residual. More...

#include <frame-velocity.hpp>

Inheritance diagram for ResidualModelFrameVelocityTpl< _Scalar >:
ResidualModelAbstractTpl< _Scalar >

Public Types

typedef ResidualModelAbstractTpl< Scalar > Base
 
typedef ResidualDataFrameVelocityTpl< Scalar > Data
 
typedef DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef pinocchio::MotionTpl< Scalar > Motion
 
typedef ResidualDataAbstractTpl< Scalar > ResidualDataAbstract
 
typedef StateMultibodyTpl< Scalar > StateMultibody
 
typedef MathBase::VectorXs VectorXs
 
- Public Types inherited from ResidualModelAbstractTpl< _Scalar >
typedef ActivationDataAbstractTpl< Scalar > ActivationDataAbstract
 
typedef CostDataAbstractTpl< Scalar > CostDataAbstract
 
typedef DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
typedef MathBase::DiagonalMatrixXs DiagonalMatrixXs
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef ResidualDataAbstractTpl< Scalar > ResidualDataAbstract
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 ResidualModelFrameVelocityTpl (boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Motion &velocity, const pinocchio::ReferenceFrame type)
 Initialize the frame velocity residual model. More...
 
 ResidualModelFrameVelocityTpl (boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Motion &velocity, const pinocchio::ReferenceFrame type, const std::size_t nu)
 Initialize the frame velocity residual model. More...
 
virtual void calc (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the frame velocity residual vector. 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 frame velocity residual. More...
 
virtual boost::shared_ptr< ResidualDataAbstractcreateData (DataCollectorAbstract *const data)
 Create the frame velocity residual data.
 
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.
 
virtual void print (std::ostream &os) const
 Print relevant information of the frame-velocity residual. More...
 
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.
 
- 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)
 Initialize the residual model. More...
 
 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 calcCostDiff (const boost::shared_ptr< CostDataAbstract > &cdata, const boost::shared_ptr< ResidualDataAbstract > &rdata, const boost::shared_ptr< ActivationDataAbstract > &adata, const bool update_u=true)
 Compute the derivative of the cost function. 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...
 
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.
 

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 nr_
 Residual vector dimension.
 
std::size_t nu_
 Control dimension.
 
boost::shared_ptr< StateAbstractstate_
 State description.
 
bool u_dependent_
 
- Protected Attributes inherited from ResidualModelAbstractTpl< _Scalar >
std::size_t nr_
 Residual vector dimension.
 
std::size_t nu_
 Control dimension.
 
bool q_dependent_
 
boost::shared_ptr< StateAbstractstate_
 State description.
 
bool u_dependent_
 
VectorXs unone_
 No control vector.
 
bool v_dependent_
 

Detailed Description

template<typename _Scalar>
class crocoddyl::ResidualModelFrameVelocityTpl< _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.

See also
ResidualModelAbstractTpl, calc(), calcDiff(), createData()

Definition at line 40 of file frame-velocity.hpp.

Constructor & Destructor Documentation

◆ ResidualModelFrameVelocityTpl() [1/2]

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

Initialize the frame velocity residual model.

Parameters
[in]stateState of the multibody system
[in]idReference frame id
[in]velocityReference velocity
[in]typeReference type of velocity (WORLD, LOCAL, LOCAL_WORLD_ALIGNED)
[in]nuDimension of the control vector

◆ ResidualModelFrameVelocityTpl() [2/2]

ResidualModelFrameVelocityTpl ( boost::shared_ptr< StateMultibody state,
const pinocchio::FrameIndex  id,
const Motion &  velocity,
const pinocchio::ReferenceFrame  type 
)

Initialize the frame velocity residual model.

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

Parameters
[in]stateState of the multibody system
[in]idReference frame id
[in]velocityReference velocity
[in]typeReference type of velocity (WORLD, LOCAL, LOCAL_WORLD_ALIGNED)

Member Function Documentation

◆ calc()

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

Compute the frame velocity residual vector.

Parameters
[in]dataFrame velocity 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()

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 frame velocity residual.

Parameters
[in]dataFrame velocity residual data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

◆ print()

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

Print relevant information of the frame-velocity residual.

Parameters
[out]osOutput stream object

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

Member Data Documentation

◆ u_dependent_

bool u_dependent_
protected

Label that indicates if the residual function depends on u

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


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