crocoddyl  1.4.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
DifferentialActionModelAbstractTpl< _Scalar > Class Template Referenceabstract

Abstract class for differential action model. More...

#include <crocoddyl/core/diff-action-base.hpp>

Inheritance diagram for DifferentialActionModelAbstractTpl< _Scalar >:

Public Types

typedef DifferentialActionDataAbstractTpl< Scalar > DifferentialActionDataAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 DifferentialActionModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t &nu, const std::size_t &nr=0)
 Initialize the differential action model. More...
 
virtual void calc (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)=0
 Compute the system acceleration and cost value. More...
 
void calc (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
virtual void calcDiff (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)=0
 Compute the derivatives of the dynamics and cost functions. More...
 
void calcDiff (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
virtual bool checkData (const boost::shared_ptr< DifferentialActionDataAbstract > &data)
 Checks that a specific data belongs to this model.
 
virtual boost::shared_ptr< DifferentialActionDataAbstractcreateData ()
 Create the differential action data. More...
 
bool const & get_has_control_limits () const
 Indicates if there are defined control limits.
 
const std::size_t & get_nr () const
 Return the dimension of the cost-residual vector.
 
const std::size_t & get_nu () const
 Return the dimension of the control input.
 
const boost::shared_ptr< StateAbstract > & get_state () const
 Return the state.
 
const VectorXs & get_u_lb () const
 Return the control lower bound.
 
const VectorXs & get_u_ub () const
 Return the control upper bound.
 
void set_u_lb (const VectorXs &u_lb)
 Modify the control lower bounds.
 
void set_u_ub (const VectorXs &u_ub)
 Modify the control upper bounds.
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Protected Member Functions

void update_has_control_limits ()
 

Protected Attributes

bool has_control_limits_
 Indicates whether any of the control limits is finite.
 
std::size_t nr_
 Dimension of the cost residual.
 
std::size_t nu_
 Control dimension.
 
boost::shared_ptr< StateAbstractstate_
 Model of the state.
 
VectorXs u_lb_
 Lower control limits.
 
VectorXs u_ub_
 Upper control limits.
 
VectorXs unone_
 Neutral state.
 

Detailed Description

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

Abstract class for differential action model.

A differential action model describes a time-continuous action model with a first-order ODE, i.e.

\[ \dot{\mathbf{v}} = \mathbf{f}(\mathbf{q}, \mathbf{v}, \mathbf{u}) \]

where the configuration \(\mathbf{q}\in\mathcal{Q}\) lies in the configuration manifold described with a nq-tuple, the velocity \(\mathbf{v}\in T_{\mathbf{q}}\mathcal{Q}\) its a tangent vector to this manifold with nv dimension, and \(\mathbf{u}\in\mathbb{R}^{nu}\) is the input commands. Both, configuration and velocity, describes the system space \(\mathbf{x}\in\mathbf{X}\) which lies in the state manifold. Note that the acceleration \(\dot{\mathbf{v}}\in T_{\mathbf{q}}\mathcal{Q}\) lies also in the tangent space of the configuration manifold.

calc computes the acceleration and cost and calcDiff computes the derivatives of the dynamics and cost function. Concretely speaking, calcDiff builds a linear-quadratic approximation of the differential action, where the dynamics and cost functions have linear and quadratic forms, respectively. \(\mathbf{f_x}\in\mathbb{R}^{nv\times ndx}\), \(\mathbf{f_u}\in\mathbb{R}^{nv\times nu}\) are the Jacobians of the dynamics; \(\mathbf{l_x}\in\mathbb{R}^{ndx}\), \(\mathbf{l_u}\in\mathbb{R}^{nu}\), \(\mathbf{l_{xx}}\in\mathbb{R}^{ndx\times ndx}\), \(\mathbf{l_{xu}}\in\mathbb{R}^{ndx\times nu}\), \(\mathbf{l_{uu}}\in\mathbb{R}^{nu\times nu}\) are the Jacobians and Hessians of the cost function, respectely.

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

Definition at line 47 of file diff-action-base.hpp.

Constructor & Destructor Documentation

◆ DifferentialActionModelAbstractTpl()

DifferentialActionModelAbstractTpl ( boost::shared_ptr< StateAbstract state,
const std::size_t &  nu,
const std::size_t &  nr = 0 
)

Initialize the differential action model.

Parameters
[in]stateState Dimension of state configuration tuple
[in]nuDimension of control vector
[in]nrDimension of cost-residual vector

Member Function Documentation

◆ calc() [1/2]

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

Compute the system acceleration and cost value.

Parameters
[in]dataDifferential action data
[in]xState point
[in]uControl input

Implemented in DifferentialActionModelFreeFwdDynamicsTpl< _Scalar >, and DifferentialActionModelNumDiffTpl< _Scalar >.

◆ calcDiff() [1/2]

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

Compute the derivatives of the dynamics and cost functions.

It computes the partial derivatives of the dynamical system and the cost function. It assumes that calc has been run first. This function builds a quadratic approximation of the time-continuous action model (i.e. dynamical system and cost function).

Parameters
[in]dataDifferential action data
[in]xState point
[in]uControl input

Implemented in DifferentialActionModelFreeFwdDynamicsTpl< _Scalar >, and DifferentialActionModelNumDiffTpl< _Scalar >.

◆ createData()

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

◆ calc() [2/2]

void calc ( const boost::shared_ptr< DifferentialActionDataAbstract > &  data,
const Eigen::Ref< const VectorXs > &  x 
)
Parameters
[in]dataDifferential action data
[in]xState point

◆ calcDiff() [2/2]

void calcDiff ( const boost::shared_ptr< DifferentialActionDataAbstract > &  data,
const Eigen::Ref< const VectorXs > &  x 
)
Parameters
[in]dataDifferential action data
[in]xState point

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