crocoddyl 1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
 
Loading...
Searching...
No Matches
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)
 Compute the total cost value for nodes that depends only on the state. 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...
 
virtual void calcDiff (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Compute the derivatives of the cost functions with respect to the state only. More...
 
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...
 
virtual bool checkData (const boost::shared_ptr< DifferentialActionDataAbstract > &data)
 Checks that a specific data belongs to this model. More...
 
virtual boost::shared_ptr< DifferentialActionDataAbstractcreateData ()
 Create the differential action data. More...
 
bool get_has_control_limits () const
 Indicates if there are defined control limits.
 
std::size_t get_nr () const
 Return the dimension of the cost-residual vector.
 
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.
 
virtual void print (std::ostream &os) const
 Print relevant information of the differential action model. More...
 
virtual void quasiStatic (const boost::shared_ptr< DifferentialActionDataAbstract > &data, Eigen::Ref< VectorXs > u, const Eigen::Ref< const VectorXs > &x, const std::size_t maxiter=100, const Scalar tol=Scalar(1e-9))
 Computes the quasic static commands. More...
 
VectorXs quasiStatic_x (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const VectorXs &x, const std::size_t maxiter=100, const Scalar tol=Scalar(1e-9))
 
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. More...
 
std::size_t nr_
 Dimension of the cost residual. More...
 
std::size_t nu_
 Control dimension. More...
 
boost::shared_ptr< StateAbstractstate_
 Model of the state. More...
 
VectorXs u_lb_
 Lower control limits. More...
 
VectorXs u_ub_
 Upper control limits. More...
 
VectorXs unone_
 Neutral state. More...
 

Friends

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

Detailed Description

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

Abstract class for differential action model.

A differential action model is the time-continuous version of an action model, i.e.

\[ \begin{aligned} &\dot{\mathbf{v}} = \mathbf{f}(\mathbf{q}, \mathbf{v}, \mathbf{u}), &\textrm{(dynamics)}\\ &l(\mathbf{x},\mathbf{u}) = \int_0^{\delta t} a(\mathbf{r}(\mathbf{x},\mathbf{u}))\,dt, &\textrm{(cost)} \end{aligned} \]

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, \(\mathbf{u}\in\mathbb{R}^{nu}\) is the input commands, \(\mathbf{r}\) and \(a\) is a residual and activation functions (see ActivationModelAbstractTpl). Both configuration and velocity describe 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.

The main computations are carrying out in calc and calcDiff. 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, respectively. Additionally, it is important remark that calcDiff() computes the derivates using the latest stored values by calc(). Thus, we need to run first calc().

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

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

Member Typedef Documentation

◆ MathBase

typedef MathBaseTpl<Scalar> MathBase

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

◆ DifferentialActionDataAbstract

◆ StateAbstract

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

◆ VectorXs

typedef MathBase::VectorXs VectorXs

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

◆ MatrixXs

typedef MathBase::MatrixXs MatrixXs

Definition at line 62 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 description
[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 \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

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

◆ calc() [2/2]

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

Compute the total cost value for nodes that depends only on the state.

It updates the total cost and the system acceleration is not updated as the control input is undefined. This function is used in the terminal nodes of an optimal control problem.

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

Reimplemented in DifferentialActionModelLQRTpl< _Scalar >, DifferentialActionModelNumDiffTpl< _Scalar >, DifferentialActionModelContactFwdDynamicsTpl< _Scalar >, and DifferentialActionModelFreeFwdDynamicsTpl< _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 \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

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

◆ calcDiff() [2/2]

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

Compute the derivatives of the cost functions with respect to the state only.

It updates the derivatives of the cost function with respect to the state only. This function is used in the terminal nodes of an optimal control problem.

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

Reimplemented in DifferentialActionModelLQRTpl< _Scalar >, DifferentialActionModelNumDiffTpl< _Scalar >, DifferentialActionModelContactFwdDynamicsTpl< _Scalar >, and DifferentialActionModelFreeFwdDynamicsTpl< _Scalar >.

◆ createData()

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

◆ checkData()

virtual bool checkData ( const boost::shared_ptr< DifferentialActionDataAbstract > &  data)
virtual

◆ quasiStatic()

virtual void quasiStatic ( const boost::shared_ptr< DifferentialActionDataAbstract > &  data,
Eigen::Ref< VectorXs >  u,
const Eigen::Ref< const VectorXs > &  x,
const std::size_t  maxiter = 100,
const Scalar  tol = Scalar(1e-9) 
)
virtual

Computes the quasic static commands.

The quasic static commands are the ones produced for a the reference posture as an equilibrium point, i.e. for \(\mathbf{f}(\mathbf{q},\mathbf{v}=\mathbf{0},\mathbf{u})=\mathbf{0}\)

Parameters
[in]dataDifferential action data
[out]uQuasic static commands
[in]xState point (velocity has to be zero)
[in]maxiterMaximum allowed number of iterations
[in]tolTolerance

Reimplemented in DifferentialActionModelContactFwdDynamicsTpl< _Scalar >, and DifferentialActionModelFreeFwdDynamicsTpl< _Scalar >.

◆ quasiStatic_x()

VectorXs quasiStatic_x ( const boost::shared_ptr< DifferentialActionDataAbstract > &  data,
const VectorXs &  x,
const std::size_t  maxiter = 100,
const Scalar  tol = Scalar(1e-9) 
)

Parameters
[in]dataDifferential action data
[in]xState point (velocity has to be zero)
[in]maxiterMaximum allowed number of iterations
[in]tolTolerance
Returns
Quasic static commands

◆ print()

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

Print relevant information of the differential action model.

Parameters
[out]osOutput stream object

Reimplemented in DifferentialActionModelLQRTpl< _Scalar >, DifferentialActionModelContactFwdDynamicsTpl< _Scalar >, and DifferentialActionModelFreeFwdDynamicsTpl< _Scalar >.

Member Data Documentation

◆ Scalar

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar

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

◆ nu_

std::size_t nu_
protected

Control dimension.

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

◆ nr_

std::size_t nr_
protected

Dimension of the cost residual.

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

◆ state_

boost::shared_ptr<StateAbstract> state_
protected

Model of the state.

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

◆ unone_

VectorXs unone_
protected

Neutral state.

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

◆ u_lb_

VectorXs u_lb_
protected

Lower control limits.

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

◆ u_ub_

VectorXs u_ub_
protected

Upper control limits.

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

◆ has_control_limits_

bool has_control_limits_
protected

Indicates whether any of the control limits is finite.

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


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