Crocoddyl
ResidualModelJointEffortTpl< _Scalar > Class Template Reference

Define a joint-effort residual. More...

#include <joint-effort.hpp>

Inheritance diagram for ResidualModelJointEffortTpl< _Scalar >:
ResidualModelAbstractTpl< _Scalar >

Public Types

typedef ActuationModelAbstractTpl< Scalar > ActuationModelAbstract
 
typedef ResidualModelAbstractTpl< Scalar > Base
 
typedef ResidualDataJointEffortTpl< Scalar > Data
 
typedef DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef ResidualDataAbstractTpl< Scalar > ResidualDataAbstract
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 
- Public Types inherited from ResidualModelAbstractTpl< _Scalar >
typedef ActivationDataAbstractTpl< Scalar > ActivationDataAbstract
 
typedef CostDataAbstractTpl< Scalar > CostDataAbstract
 
typedef DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
typedef MathBase::DiagonalMatrixXs DiagonalMatrixXs
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef ResidualDataAbstractTpl< Scalar > ResidualDataAbstract
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 ResidualModelJointEffortTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActuationModelAbstract > actuation)
 Initialize the joint-effort residual model. More...
 
 ResidualModelJointEffortTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActuationModelAbstract > actuation, const std::size_t nu)
 Initialize the joint-effort residual model. More...
 
 ResidualModelJointEffortTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActuationModelAbstract > actuation, const VectorXs &uref)
 Initialize the joint-effort residual model. More...
 
 ResidualModelJointEffortTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActuationModelAbstract > actuation, const VectorXs &uref, const std::size_t nu, const bool fwddyn=false)
 Initialize the joint-effort residual model. More...
 
virtual void calc (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
virtual void calc (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the joint-effort residual. More...
 
virtual void calcDiff (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 
virtual void calcDiff (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the derivatives of the joint-effort residual. More...
 
virtual boost::shared_ptr< ResidualDataAbstractcreateData (DataCollectorAbstract *const data)
 Create the joint-effort residual data.
 
const VectorXs & get_reference () const
 Return the reference joint-effort vector.
 
virtual void print (std::ostream &os) const
 Print relevant information of the joint-effort residual. More...
 
void set_reference (const VectorXs &reference)
 Modify the reference joint-effort vector.
 
- Public Member Functions inherited from ResidualModelAbstractTpl< _Scalar >
 ResidualModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nr, const bool q_dependent=true, const bool v_dependent=true, const bool u_dependent=true)
 Initialize the residual model. More...
 
 ResidualModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nr, const std::size_t nu, const bool q_dependent=true, const bool v_dependent=true, const bool u_dependent=true)
 Initialize the residual model. More...
 
virtual void calcCostDiff (const boost::shared_ptr< CostDataAbstract > &cdata, const boost::shared_ptr< ResidualDataAbstract > &rdata, const boost::shared_ptr< ActivationDataAbstract > &adata, const bool update_u=true)
 Compute the derivative of the cost function. More...
 
std::size_t get_nr () const
 Return the dimension of the residual vector.
 
std::size_t get_nu () const
 Return the dimension of the control input.
 
bool get_q_dependent () const
 Return true if the residual function depends on q.
 
const boost::shared_ptr< StateAbstract > & get_state () const
 Return the state.
 
bool get_u_dependent () const
 Return true if the residual function depends on u.
 
bool get_v_dependent () const
 Return true if the residual function depends on v.
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 
- Public Attributes inherited from ResidualModelAbstractTpl< _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Protected Attributes

std::size_t nr_
 Residual vector dimension.
 
std::size_t nu_
 Control dimension.
 
bool q_dependent_
 
boost::shared_ptr< StateAbstractstate_
 State description.
 
bool v_dependent_
 
- Protected Attributes inherited from ResidualModelAbstractTpl< _Scalar >
std::size_t nr_
 Residual vector dimension.
 
std::size_t nu_
 Control dimension.
 
bool q_dependent_
 
boost::shared_ptr< StateAbstractstate_
 State description.
 
bool u_dependent_
 
VectorXs unone_
 No control vector.
 
bool v_dependent_
 

Detailed Description

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

Define a joint-effort residual.

This residual function is defined as \(\mathbf{r}=\mathbf{u}-\mathbf{u}^*\), where \(\mathbf{u},\mathbf{u}^*\in~\mathbb{R}^{nu}\) are the current and reference joint effort inputs, respectively. Note that the dimension of the residual vector is obtained from ActuationModelAbstract::nu.

Both residual and residual Jacobians are computed analytically.

As described in ResidualModelAbstractTpl(), the residual value and its Jacobians are calculated by calc and calcDiff, respectively.

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

Definition at line 36 of file joint-effort.hpp.

Constructor & Destructor Documentation

◆ ResidualModelJointEffortTpl() [1/4]

ResidualModelJointEffortTpl ( boost::shared_ptr< StateAbstract state,
boost::shared_ptr< ActuationModelAbstract actuation,
const VectorXs &  uref,
const std::size_t  nu,
const bool  fwddyn = false 
)

Initialize the joint-effort residual model.

Parameters
[in]stateState description
[in]actuationActuation model
[in]urefReference joint effort
[in]nuDimension of the control vector
[in]fwddynIndicates that we have a forward dynamics problem (true) or inverse dynamics (false) (default false)

◆ ResidualModelJointEffortTpl() [2/4]

ResidualModelJointEffortTpl ( boost::shared_ptr< StateAbstract state,
boost::shared_ptr< ActuationModelAbstract actuation,
const VectorXs &  uref 
)

Initialize the joint-effort residual model.

The default nu value is obtained from StateAbstractTpl::get_nv().

Parameters
[in]stateState description
[in]actuationActuation model
[in]urefReference joint effort

◆ ResidualModelJointEffortTpl() [3/4]

ResidualModelJointEffortTpl ( boost::shared_ptr< StateAbstract state,
boost::shared_ptr< ActuationModelAbstract actuation,
const std::size_t  nu 
)

Initialize the joint-effort residual model.

The default reference joint effort is obtained from MathBaseTpl<>::VectorXs::Zero(actuation->get_nu()).

Parameters
[in]stateState description
[in]actuationActuation model
[in]nuDimension of the control vector

◆ ResidualModelJointEffortTpl() [4/4]

ResidualModelJointEffortTpl ( boost::shared_ptr< StateAbstract state,
boost::shared_ptr< ActuationModelAbstract actuation 
)

Initialize the joint-effort residual model.

The default reference joint effort is obtained from MathBaseTpl<>::VectorXs::Zero(actuation->get_nu()). The default nu value is obtained from StateAbstractTpl::get_nv().

Parameters
[in]stateState description
[in]actuationActuation model

Member Function Documentation

◆ calc() [1/2]

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

Compute the joint-effort residual.

Parameters
[in]dataJoint-effort residual data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

◆ calc() [2/2]

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

It updates the residual vector based on the state only. This function is used in the terminal nodes of an optimal control problem.

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

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

◆ calcDiff() [1/2]

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

Compute the derivatives of the joint-effort residual.

Parameters
[in]dataJoint-effort residual data
[in]xState point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
[in]uControl input \(\mathbf{u}\in\mathbb{R}^{nu}\)

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

◆ calcDiff() [2/2]

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

◆ print()

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

Print relevant information of the joint-effort residual.

Parameters
[out]osOutput stream object

Reimplemented from ResidualModelAbstractTpl< _Scalar >.

Member Data Documentation

◆ q_dependent_

bool q_dependent_
protected

Label that indicates if the residual function depends on q

Definition at line 229 of file residual-base.hpp.

◆ v_dependent_

bool v_dependent_
protected

Label that indicates if the residual function depends on v

Definition at line 231 of file residual-base.hpp.


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