crocoddyl  1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
DifferentialActionModelNumDiffTpl< _Scalar > Class Template Reference

This class computes the numerical differentiation of a differential action model. More...

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

Inheritance diagram for DifferentialActionModelNumDiffTpl< _Scalar >:
Collaboration diagram for DifferentialActionModelNumDiffTpl< _Scalar >:

Public Types

typedef DifferentialActionModelAbstractTpl< Scalar > Base
 
typedef DifferentialActionDataNumDiffTpl< Scalar > Data
 
typedef DifferentialActionDataAbstractTpl< Scalar > DifferentialActionDataAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef MathBase::VectorXs VectorXs
 
- Public Types inherited from DifferentialActionModelAbstractTpl< _Scalar >
typedef DifferentialActionDataAbstractTpl< Scalar > DifferentialActionDataAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 DifferentialActionModelNumDiffTpl (boost::shared_ptr< Base > model, const bool with_gauss_approx=false)
 Initialize the numdiff differential action model. More...
 
virtual void calc (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
virtual void calc (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the system acceleration and cost value. More...
 
virtual void calcDiff (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)
 Compute the derivatives of the dynamics and cost functions. More...
 
virtual boost::shared_ptr< DifferentialActionDataAbstractcreateData ()
 Create the differential action data. More...
 
const Scalar get_disturbance () const
 Return the disturbance used in the numerical differentiation routine.
 
const boost::shared_ptr< Base > & get_model () const
 Return the differential acton model that we use to numerical differentiate.
 
bool get_with_gauss_approx ()
 Identify if the Gauss approximation is going to be used or not.
 
void set_disturbance (const Scalar disturbance)
 Modify the disturbance used in the numerical differentiation routine.
 
- Public Member Functions inherited from DifferentialActionModelAbstractTpl< _Scalar >
 DifferentialActionModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nu, const std::size_t nr=0)
 Initialize the differential action model. More...
 
virtual bool checkData (const boost::shared_ptr< DifferentialActionDataAbstract > &data)
 Checks that a specific data belongs to this model.
 
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
 
- Public Attributes inherited from DifferentialActionModelAbstractTpl< _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Protected Attributes

bool has_control_limits_
 Indicates whether any of the control limits is finite.
 
std::size_t nr_
 < Indicates whether any of the control limits
 
std::size_t nu_
 < Dimension of the cost residual
 
boost::shared_ptr< StateAbstractstate_
 < Control dimension
 
VectorXs u_lb_
 < Model of the state
 
VectorXs u_ub_
 < Lower control limits
 
VectorXs unone_
 < Upper control limits
 
- Protected Attributes inherited from DifferentialActionModelAbstractTpl< _Scalar >
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.
 

Additional Inherited Members

- Protected Member Functions inherited from DifferentialActionModelAbstractTpl< _Scalar >
void update_has_control_limits ()
 

Detailed Description

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

This class computes the numerical differentiation of a differential action model.

It computes Jacobian of the cost, its residual and dynamics via numerical differentiation. It considers that the action model owns a cost residual and the cost is the square of this residual, i.e., \(\ell(\mathbf{x},\mathbf{u})=\frac{1}{2}\|\mathbf{r}(\mathbf{x},\mathbf{u})\|^2\), where \(\mathbf{r}(\mathbf{x},\mathbf{u})\) is the residual vector. The Hessian is computed only through the Gauss-Newton approximation, i.e.,

\begin{eqnarray*} \mathbf{\ell}_\mathbf{xx} &=& \mathbf{R_x}^T\mathbf{R_x} \\ \mathbf{\ell}_\mathbf{uu} &=& \mathbf{R_u}^T\mathbf{R_u} \\ \mathbf{\ell}_\mathbf{xu} &=& \mathbf{R_x}^T\mathbf{R_u} \end{eqnarray*}

where the Jacobians of the cost residuals are denoted by \(\mathbf{R_x}\) and \(\mathbf{R_u}\). Note that this approximation ignores the tensor products (e.g., \(\mathbf{R_{xx}}\mathbf{r}\)).

Finally, in the case that the cost does not have a residual, we set the Hessian to zero, i.e., \(\mathbf{L_{xx}} = \mathbf{L_{xu}} = \mathbf{L_{uu}} = \mathbf{0}\).

See also
DifferentialActionModelAbstractTpl(), calcDiff()

Definition at line 42 of file diff-action.hpp.

Constructor & Destructor Documentation

◆ DifferentialActionModelNumDiffTpl()

DifferentialActionModelNumDiffTpl ( boost::shared_ptr< Base model,
const bool  with_gauss_approx = false 
)
explicit

Initialize the numdiff differential action model.

Parameters
[in]modelDifferential action model that we want to apply the numerical differentiation
[in]with_gauss_approxTrue if we want to use the Gauss approximation for computing the Hessians

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

Implements DifferentialActionModelAbstractTpl< _Scalar >.

◆ calc() [2/2]

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

◆ calcDiff() [1/2]

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

Implements DifferentialActionModelAbstractTpl< _Scalar >.

◆ calcDiff() [2/2]

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

◆ createData()

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

Create the differential action data.

Returns
the differential action data

Reimplemented from DifferentialActionModelAbstractTpl< _Scalar >.


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