Crocoddyl
DifferentialActionModelLQRTpl< _Scalar > Class Template Reference
Inheritance diagram for DifferentialActionModelLQRTpl< _Scalar >:
DifferentialActionModelAbstractTpl< _Scalar >

Public Types

typedef DifferentialActionModelAbstractTpl< Scalar > Base
 
typedef DifferentialActionDataLQRTpl< Scalar > Data
 
typedef DifferentialActionDataAbstractTpl< Scalar > DifferentialActionDataAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef _Scalar Scalar
 
typedef StateVectorTpl< Scalar > StateVector
 
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

 DifferentialActionModelLQRTpl (const std::size_t nq, const std::size_t nu, const bool drift_free=true)
 
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)
 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)
 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.
 
virtual boost::shared_ptr< DifferentialActionDataAbstractcreateData ()
 Create the differential action data. More...
 
const VectorXs & get_f0 () const
 
const MatrixXs & get_Fq () const
 
const MatrixXs & get_Fu () const
 
const MatrixXs & get_Fv () const
 
const VectorXs & get_lu () const
 
const MatrixXs & get_Luu () const
 
const VectorXs & get_lx () const
 
const MatrixXs & get_Lxu () const
 
const MatrixXs & get_Lxx () const
 
virtual void print (std::ostream &os) const
 Print relevant information of the LQR model. More...
 
void set_f0 (const VectorXs &f0)
 
void set_Fq (const MatrixXs &Fq)
 
void set_Fu (const MatrixXs &Fu)
 
void set_Fv (const MatrixXs &Fv)
 
void set_lu (const VectorXs &lu)
 
void set_Luu (const MatrixXs &Luu)
 
void set_lx (const VectorXs &lx)
 
void set_Lxu (const MatrixXs &Lxu)
 
void set_Lxx (const MatrixXs &Lxx)
 
- Public Member Functions inherited from DifferentialActionModelAbstractTpl< _Scalar >
 DifferentialActionModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nu, const std::size_t nr=0, const std::size_t ng=0, const std::size_t nh=0)
 Initialize the differential action model. More...
 
virtual const VectorXs & get_g_lb () const
 Return the lower bound of the inequality constraints.
 
virtual const VectorXs & get_g_ub () const
 Return the upper bound of the inequality constraints.
 
bool get_has_control_limits () const
 Indicates if there are defined control limits.
 
virtual std::size_t get_ng () const
 Return the number of inequality constraints.
 
virtual std::size_t get_nh () const
 Return the number of equality constraints.
 
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 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_g_lb (const VectorXs &g_lb)
 Modify the lower bound of the inequality constraints.
 
void set_g_ub (const VectorXs &g_ub)
 Modify the upper bound of the inequality constraints.
 
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.
 

Protected Attributes

std::size_t nu_
 Control dimension.
 
boost::shared_ptr< StateAbstractstate_
 < Control dimension
 
- Protected Attributes inherited from DifferentialActionModelAbstractTpl< _Scalar >
VectorXs g_lb_
 Lower bound of the inequality constraints.
 
VectorXs g_ub_
 Lower bound of the inequality constraints.
 
bool has_control_limits_
 
std::size_t ng_
 Number of inequality constraints.
 
std::size_t nh_
 Number of equality constraints.
 
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

- Public Attributes inherited from DifferentialActionModelAbstractTpl< _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 
- Protected Member Functions inherited from DifferentialActionModelAbstractTpl< _Scalar >
void update_has_control_limits ()
 Update the status of the control limits (i.e. if there are defined limits)
 

Detailed Description

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

Definition at line 21 of file diff-lqr.hpp.

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

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 from DifferentialActionModelAbstractTpl< _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 
)
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

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 from DifferentialActionModelAbstractTpl< _Scalar >.

◆ createData()

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

Create the differential action data.

Returns
the differential action data

Reimplemented from DifferentialActionModelAbstractTpl< _Scalar >.

◆ print()

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

Print relevant information of the LQR model.

Parameters
[out]osOutput stream object

Reimplemented from DifferentialActionModelAbstractTpl< _Scalar >.


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