Crocoddyl
ActuationModelAbstractTpl< _Scalar > Class Template Referenceabstract

Abstract class for the actuation-mapping model. More...

#include <actuation-base.hpp>

Inheritance diagram for ActuationModelAbstractTpl< _Scalar >:
ActuationModelFloatingBaseTpl< _Scalar > ActuationModelFullTpl< _Scalar > ActuationModelMultiCopterBaseTpl< _Scalar > ActuationModelNumDiffTpl< _Scalar > ActuationSquashingModelTpl< _Scalar >

Public Types

typedef ActuationDataAbstractTpl< Scalar > ActuationDataAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 ActuationModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nu)
 Initialize the actuation model. More...
 
void calc (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Ignore the computation of the actuation signal. More...
 
virtual void calc (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)=0
 Compute the actuation signal from the state point \(\mathbf{x}\in\mathbb{R}^{ndx}\) and joint torque inputs \(\mathbf{u}\in\mathbb{R}^{nu}\). More...
 
void calcDiff (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Ignore the computation of the Jacobians of the actuation function. More...
 
virtual void calcDiff (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)=0
 Compute the Jacobians of the actuation function. More...
 
virtual void commands (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &tau)=0
 Compute the joint torque input from the generalized torques. More...
 
virtual boost::shared_ptr< ActuationDataAbstractcreateData ()
 Create the actuation data. More...
 
std::size_t get_nu () const
 Return the dimension of the joint-torque input.
 
const boost::shared_ptr< StateAbstract > & get_state () const
 Return the state.
 
virtual void print (std::ostream &os) const
 Print relevant information of the residual model. More...
 
virtual void torqueTransform (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the torque transform from generalized torques to joint torque inputs. More...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Protected Attributes

std::size_t nu_
 Dimension of joint torque inputs.
 
boost::shared_ptr< StateAbstractstate_
 Model of the state.
 

Friends

template<class Scalar >
std::ostream & operator<< (std::ostream &os, const ResidualModelAbstractTpl< Scalar > &model)
 Print information on the residual model.
 

Detailed Description

template<typename _Scalar>
class crocoddyl::ActuationModelAbstractTpl< _Scalar >

Abstract class for the actuation-mapping model.

The generalized torques \(\boldsymbol{\tau}\in\mathbb{R}^{nv}\) can by any nonlinear function of the joint-torque inputs \(\mathbf{u}\in\mathbb{R}^{nu}\), and state point \(\mathbf{x}\in\mathbb{R}^{nx}\), where nv, nu, and ndx are the number of joints, dimension of the joint torque input and state manifold, respectively. Additionally, the generalized torques are also named as the actuation signals of our system.

The main computations are carried out in calc(), and calcDiff(), where the former computes actuation signal, and the latter computes the Jacobians of the actuation-mapping function, i.e., \(\frac{\partial\boldsymbol{\tau}}{\partial\mathbf{x}}\) and \(\frac{\partial\boldsymbol{\tau}}{\partial\mathbf{u}}\). Note that calcDiff() requires to run calc() first.

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

Definition at line 45 of file actuation-base.hpp.

Constructor & Destructor Documentation

◆ ActuationModelAbstractTpl()

ActuationModelAbstractTpl ( boost::shared_ptr< StateAbstract state,
const std::size_t  nu 
)

Initialize the actuation model.

Parameters
[in]stateState description
[in]nuDimension of joint-torque input

Member Function Documentation

◆ calc() [1/2]

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

Compute the actuation signal from the state point \(\mathbf{x}\in\mathbb{R}^{ndx}\) and joint torque inputs \(\mathbf{u}\in\mathbb{R}^{nu}\).

Parameters
[in]dataActuation data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uJoint-torque input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Implemented in ActuationModelMultiCopterBaseTpl< _Scalar >, ActuationModelFullTpl< _Scalar >, ActuationModelFloatingBaseTpl< _Scalar >, ActuationModelNumDiffTpl< _Scalar >, and ActuationSquashingModelTpl< _Scalar >.

◆ calc() [2/2]

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

Ignore the computation of the actuation signal.

It does not update the actuation signal as this function is used in the terminal nodes of an optimal control problem.

Parameters
[in]dataActuation data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)

◆ calcDiff() [1/2]

virtual void calcDiff ( const boost::shared_ptr< ActuationDataAbstract > &  data,
const Eigen::Ref< const VectorXs > &  x,
const Eigen::Ref< const VectorXs > &  u 
)
pure virtual

Compute the Jacobians of the actuation function.

Parameters
[in]dataActuation data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uJoint-torque input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Implemented in ActuationModelMultiCopterBaseTpl< _Scalar >, ActuationModelFullTpl< _Scalar >, ActuationModelFloatingBaseTpl< _Scalar >, ActuationModelNumDiffTpl< _Scalar >, and ActuationSquashingModelTpl< _Scalar >.

◆ calcDiff() [2/2]

void calcDiff ( const boost::shared_ptr< ActuationDataAbstract > &  data,
const Eigen::Ref< const VectorXs > &  x 
)

Ignore the computation of the Jacobians of the actuation function.

It does not update the Jacobians of the actuation function as this function is used in the terminal nodes of an optimal control problem.

Parameters
[in]dataActuation data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)

◆ commands()

virtual void commands ( const boost::shared_ptr< ActuationDataAbstract > &  data,
const Eigen::Ref< const VectorXs > &  x,
const Eigen::Ref< const VectorXs > &  tau 
)
pure virtual

Compute the joint torque input from the generalized torques.

It stores the results in ActuationDataAbstractTpl::u.

Parameters
[in]dataActuation data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]tauGeneralized torques \(\mathbf{u}\in\mathbb{R}^{nv}\)

Implemented in ActuationModelMultiCopterBaseTpl< _Scalar >, ActuationModelFullTpl< _Scalar >, ActuationModelFloatingBaseTpl< _Scalar >, ActuationModelNumDiffTpl< _Scalar >, and ActuationSquashingModelTpl< _Scalar >.

◆ torqueTransform()

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

Compute the torque transform from generalized torques to joint torque inputs.

It stores the results in ActuationDataAbstractTpl::Mtau.

Parameters
[in]dataActuation data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]tauJoint-torque inputs \(\mathbf{u}\in\mathbb{R}^{nu}\)

Reimplemented in ActuationModelMultiCopterBaseTpl< _Scalar >, ActuationModelFullTpl< _Scalar >, and ActuationModelFloatingBaseTpl< _Scalar >.

◆ createData()

◆ print()

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

Print relevant information of the residual model.

Parameters
[out]osOutput stream object

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