crocoddyl  1.4.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
DifferentialActionModelNumDiffTpl< _Scalar > Class Template Reference
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, bool with_gauss_approx=false)
 
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, 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
 
const boost::shared_ptr< Base > & get_model () const
 
bool get_with_gauss_approx ()
 
void set_disturbance (const Scalar &disturbance)
 
- 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...
 
void calc (const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
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.
 
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
 
- Public Attributes inherited from DifferentialActionModelAbstractTpl< _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Additional Inherited Members

- Protected Member Functions inherited from DifferentialActionModelAbstractTpl< _Scalar >
void update_has_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.
 

Detailed Description

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

Definition at line 125 of file fwd.hpp.

Member Function Documentation

◆ calc()

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
[in]uControl input

Implements DifferentialActionModelAbstractTpl< _Scalar >.

◆ calcDiff()

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
[in]uControl input

Implements DifferentialActionModelAbstractTpl< _Scalar >.

◆ 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: