Crocoddyl
ActuationModelNumDiffTpl< _Scalar > Class Template Reference

This class computes the numerical differentiation of an actuation model. More...

#include <actuation.hpp>

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

Public Types

typedef ActuationDataAbstractTpl< Scalar > ActuationDataAbstract
 
typedef ActuationModelAbstractTpl< Scalar > Base
 
typedef ActuationDataNumDiffTpl< Scalar > Data
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef _Scalar Scalar
 
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

 ActuationModelNumDiffTpl (boost::shared_ptr< Base > model)
 Initialize the numdiff residual model. More...
 
virtual ~ActuationModelNumDiffTpl ()
 Destroy the numdiff actuation model.
 
virtual void calc (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
virtual void calc (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 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...
 
virtual void calcDiff (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
virtual void calcDiff (const boost::shared_ptr< ActuationDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 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)
 Compute the joint torque input from the generalized torques. More...
 
virtual boost::shared_ptr< ActuationDataAbstractcreateData ()
 Create the actuation data. More...
 
const Scalar get_disturbance () const
 Return the disturbance constant used by the numerical differentiation routine.
 
const boost::shared_ptr< Base > & get_model () const
 Return the original actuation model.
 
void set_disturbance (const Scalar disturbance)
 Modify the disturbance constant used by the numerical differentiation routine.
 
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 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.
 
- 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::ActuationModelNumDiffTpl< _Scalar >

This class computes the numerical differentiation of an actuation model.

It computes the Jacobian of the residual model via numerical differentiation, i.e., \(\frac{\partial\boldsymbol{\tau}}{\partial\mathbf{x}}\) and \(\frac{\partial\boldsymbol{\tau}}{\partial\mathbf{u}}\) which denote the Jacobians of the actuation function \(\boldsymbol{\tau}(\mathbf{x},\mathbf{u})\).

See also
ActuationModelAbstractTpl(), calcDiff()

Definition at line 34 of file actuation.hpp.

Constructor & Destructor Documentation

◆ ActuationModelNumDiffTpl()

ActuationModelNumDiffTpl ( boost::shared_ptr< Base model)
explicit

Initialize the numdiff residual model.

Parameters
modelActuation model that we want to apply the numerical differentiation

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

Implements ActuationModelAbstractTpl< _Scalar >.

◆ calc() [2/2]

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

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

Implements ActuationModelAbstractTpl< _Scalar >.

◆ calcDiff() [2/2]

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

◆ commands()

virtual void commands ( const boost::shared_ptr< ActuationDataAbstract > &  data,
const Eigen::Ref< const VectorXs > &  x,
const Eigen::Ref< const VectorXs > &  tau 
)
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}\)

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

◆ createData()

virtual boost::shared_ptr<ActuationDataAbstract> createData ( )
virtual

Create the actuation data.

Returns
the actuation data

Reimplemented from ActuationModelAbstractTpl< _Scalar >.


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