Crocoddyl
ActuationModelFloatingBaseTpl< _Scalar > Class Template Reference

Floating-base actuation model. More...

#include <floating-base.hpp>

Inheritance diagram for ActuationModelFloatingBaseTpl< _Scalar >:
ActuationModelAbstractTpl< _Scalar >

Public Types

typedef ActuationModelAbstractTpl< Scalar > Base
 
typedef ActuationDataAbstractTpl< Scalar > Data
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef _Scalar Scalar
 
typedef StateMultibodyTpl< Scalar > StateMultibody
 
typedef MathBase::VectorXs VectorXs
 
- Public Types inherited from ActuationModelAbstractTpl< _Scalar >
typedef ActuationDataAbstractTpl< Scalar > ActuationDataAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 ActuationModelFloatingBaseTpl (boost::shared_ptr< StateMultibody > state)
 Initialize the floating-base actuation model. More...
 
virtual void calc (const boost::shared_ptr< Data > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &u)
 Compute the floating-base actuation signal from the joint-torque input \(\mathbf{u}\in\mathbb{R}^{nu}\). More...
 
virtual void calcDiff (const boost::shared_ptr< Data > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
 Compute the Jacobians of the floating-base actuation function. More...
 
virtual void commands (const boost::shared_ptr< Data > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &tau)
 Compute the joint torque input from the generalized torques. More...
 
virtual boost::shared_ptr< DatacreateData ()
 Create the floating-base actuation data. More...
 
virtual void torqueTransform (const boost::shared_ptr< Data > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
 Compute the torque transform from generalized torques to joint torque inputs. More...
 
- Public Member Functions inherited from ActuationModelAbstractTpl< _Scalar >
 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...
 
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...
 
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...
 

Protected Attributes

std::size_t nu_
 Dimension of joint torque inputs.
 
boost::shared_ptr< StateAbstractstate_
 Model of the state.
 
- Protected Attributes inherited from ActuationModelAbstractTpl< _Scalar >
std::size_t nu_
 Dimension of joint torque inputs.
 
boost::shared_ptr< StateAbstractstate_
 Model of the state.
 

Additional Inherited Members

- Public Attributes inherited from ActuationModelAbstractTpl< _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Detailed Description

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

Floating-base actuation model.

It considers the first joint, defined in the Pinocchio model, as the floating-base joints. Then, this joint (that might have various DoFs) is unactuated.

The main computations are carrying out in calc, and calcDiff, where the former computes actuation signal \(\mathbf{a}\) from a given joint-torque input \(\mathbf{u}\) and state point \(\mathbf{x}\), and the latter computes the Jacobians of the actuation-mapping function. Note that calcDiff requires to run calc first.

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

Definition at line 36 of file floating-base.hpp.

Constructor & Destructor Documentation

◆ ActuationModelFloatingBaseTpl()

ActuationModelFloatingBaseTpl ( boost::shared_ptr< StateMultibody state)
inlineexplicit

Initialize the floating-base actuation model.

Parameters
[in]stateState of a multibody system
[in]nuDimension of joint-torque vector

Definition at line 53 of file floating-base.hpp.

Member Function Documentation

◆ calc()

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

Compute the floating-base actuation signal from the joint-torque input \(\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}\)

Implements ActuationModelAbstractTpl< _Scalar >.

Definition at line 73 of file floating-base.hpp.

◆ calcDiff()

virtual void calcDiff ( const boost::shared_ptr< Data > &  data,
const Eigen::Ref< const VectorXs > &  ,
const Eigen::Ref< const VectorXs > &   
)
inlinevirtual

Compute the Jacobians of the floating-base 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}\)

Implements ActuationModelAbstractTpl< _Scalar >.

Definition at line 92 of file floating-base.hpp.

◆ commands()

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

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}\)

Implements ActuationModelAbstractTpl< _Scalar >.

Definition at line 106 of file floating-base.hpp.

◆ torqueTransform()

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

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 from ActuationModelAbstractTpl< _Scalar >.

Definition at line 118 of file floating-base.hpp.

◆ createData()

virtual boost::shared_ptr<Data> createData ( )
inlinevirtual

Create the floating-base actuation data.

Returns
the actuation data

Reimplemented from ActuationModelAbstractTpl< _Scalar >.

Definition at line 135 of file floating-base.hpp.


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