State cost. More...
#include <crocoddyl/multibody/costs/state.hpp>
Public Types | |
typedef ActivationModelAbstractTpl< Scalar > | ActivationModelAbstract |
typedef CostModelResidualTpl< Scalar > | Base |
typedef CostDataAbstractTpl< Scalar > | CostDataAbstract |
typedef MathBaseTpl< Scalar > | MathBase |
typedef MathBase::MatrixXs | MatrixXs |
typedef ResidualModelStateTpl< Scalar > | ResidualModelState |
typedef StateMultibodyTpl< Scalar > | StateMultibody |
typedef MathBase::VectorXs | VectorXs |
![]() | |
typedef ActivationModelAbstractTpl< Scalar > | ActivationModelAbstract |
typedef CostModelAbstractTpl< Scalar > | Base |
typedef CostDataAbstractTpl< Scalar > | CostDataAbstract |
typedef CostDataResidualTpl< Scalar > | Data |
typedef DataCollectorAbstractTpl< Scalar > | DataCollectorAbstract |
typedef MathBaseTpl< Scalar > | MathBase |
typedef MathBase::MatrixXs | MatrixXs |
typedef ResidualModelAbstractTpl< Scalar > | ResidualModelAbstract |
typedef MathBase::VectorXs | VectorXs |
![]() | |
typedef ActivationModelAbstractTpl< Scalar > | ActivationModelAbstract |
typedef ActivationModelQuadTpl< Scalar > | ActivationModelQuad |
typedef CostDataAbstractTpl< Scalar > | CostDataAbstract |
typedef DataCollectorAbstractTpl< Scalar > | DataCollectorAbstract |
typedef MathBaseTpl< Scalar > | MathBase |
typedef MathBase::MatrixXs | MatrixXs |
typedef ResidualModelAbstractTpl< Scalar > | ResidualModelAbstract |
typedef StateAbstractTpl< Scalar > | StateAbstract |
typedef MathBase::VectorXs | VectorXs |
Public Member Functions | |
CostModelStateTpl (boost::shared_ptr< typename Base::StateAbstract > state) | |
Initialize the state cost model. More... | |
CostModelStateTpl (boost::shared_ptr< typename Base::StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation) | |
Initialize the state cost model. More... | |
CostModelStateTpl (boost::shared_ptr< typename Base::StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation, const std::size_t nu) | |
Initialize the state cost model. More... | |
CostModelStateTpl (boost::shared_ptr< typename Base::StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation, const VectorXs &xref) | |
Initialize the state cost model. More... | |
CostModelStateTpl (boost::shared_ptr< typename Base::StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation, const VectorXs &xref, const std::size_t nu) | |
Initialize the state cost model. More... | |
CostModelStateTpl (boost::shared_ptr< typename Base::StateAbstract > state, const std::size_t nu) | |
Initialize the state cost model. More... | |
CostModelStateTpl (boost::shared_ptr< typename Base::StateAbstract > state, const VectorXs &xref) | |
Initialize the state cost model. More... | |
CostModelStateTpl (boost::shared_ptr< typename Base::StateAbstract > state, const VectorXs &xref, const std::size_t nu) | |
Initialize the state cost model. More... | |
virtual void | calcDiff (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) |
Compute the derivatives of the state cost. More... | |
![]() | |
CostModelResidualTpl (boost::shared_ptr< typename Base::StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation, boost::shared_ptr< ResidualModelAbstract > residual) | |
Initialize the residual cost model. More... | |
CostModelResidualTpl (boost::shared_ptr< typename Base::StateAbstract > state, boost::shared_ptr< ResidualModelAbstract > residual) | |
Initialize the residual cost model. More... | |
virtual void | calc (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) |
Compute the residual cost based on state only. More... | |
virtual void | calc (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) |
Compute the residual cost. More... | |
virtual void | calcDiff (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) |
Compute the derivatives of the residual cost with respect to the state only. More... | |
virtual boost::shared_ptr< CostDataAbstract > | createData (DataCollectorAbstract *const data) |
Create the residual cost data. | |
virtual void | print (std::ostream &os) const |
Print relevant information of the cost-residual model. More... | |
![]() | |
CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation) | |
Initialize the cost model. More... | |
CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation, boost::shared_ptr< ResidualModelAbstract > residual) | |
Initialize the cost model. More... | |
CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation, const std::size_t nu) | |
Initialize the cost model. More... | |
CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ResidualModelAbstract > residual) | |
Initialize the cost model. More... | |
CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nr) | |
Initialize the cost model. More... | |
CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nr, const std::size_t nu) | |
Initialize the cost model. More... | |
const boost::shared_ptr< ActivationModelAbstract > & | get_activation () const |
Return the activation model. | |
std::size_t | get_nu () const |
Return the dimension of the control input. | |
template<class ReferenceType > | |
ReferenceType | get_reference () |
Return the cost reference. | |
const boost::shared_ptr< ResidualModelAbstract > & | get_residual () const |
Return the residual model. | |
const boost::shared_ptr< StateAbstract > & | get_state () const |
Return the state. | |
template<class ReferenceType > | |
void | set_reference (ReferenceType ref) |
Modify the cost reference. | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
![]() | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
![]() | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
Protected Member Functions | |
virtual void | get_referenceImpl (const std::type_info &ti, void *pv) |
Return the state reference. | |
virtual void | set_referenceImpl (const std::type_info &ti, const void *pv) |
Modify the state reference. | |
Protected Attributes | |
boost::shared_ptr< ActivationModelAbstract > | activation_ |
Activation model. | |
std::size_t | nu_ |
Control dimension. | |
boost::shared_ptr< ResidualModelAbstract > | residual_ |
Residual model. | |
boost::shared_ptr< StateAbstract > | state_ |
State description. | |
VectorXs | unone_ |
No control vector. | |
![]() | |
boost::shared_ptr< ActivationModelAbstract > | activation_ |
Activation model. | |
std::size_t | nu_ |
Control dimension. | |
boost::shared_ptr< ResidualModelAbstract > | residual_ |
Residual model. | |
boost::shared_ptr< StateAbstract > | state_ |
State description. | |
VectorXs | unone_ |
No control vector. | |
![]() | |
boost::shared_ptr< ActivationModelAbstract > | activation_ |
Activation model. | |
std::size_t | nu_ |
Control dimension. | |
boost::shared_ptr< ResidualModelAbstract > | residual_ |
Residual model. | |
boost::shared_ptr< StateAbstract > | state_ |
State description. | |
VectorXs | unone_ |
No control vector. | |
State cost.
This cost function defines a residual vector as \(\mathbf{r}=\mathbf{x}\ominus\mathbf{x}^*\), where \(\mathbf{x},\mathbf{x}^*\in~\mathcal{X}\) are the current and reference states, respectively, which belong to the state manifold \(\mathcal{X}\). Note that the dimension of the residual vector is obtained from StateAbstract::get_ndx()
.
Both cost and residual derivatives are computed analytically. For the computation of the cost Hessian, we use the Gauss-Newton approximation, e.g. \(\mathbf{l_{xx}} = \mathbf{l_{x}}^T \mathbf{l_{x}} \).
As described in CostModelResidualTpl()
, the cost value and its derivatives are calculated by calc
and calcDiff
, respectively.
CostModelResidualTpl
, calc()
, calcDiff()
, createData()
CostModelStateTpl | ( | boost::shared_ptr< typename Base::StateAbstract > | state, |
boost::shared_ptr< ActivationModelAbstract > | activation, | ||
const VectorXs & | xref, | ||
const std::size_t | nu | ||
) |
Initialize the state cost model.
[in] | state | State of the multibody system |
[in] | activation | Activation model |
[in] | xref | Reference state |
[in] | nu | Dimension of the control vector |
CostModelStateTpl | ( | boost::shared_ptr< typename Base::StateAbstract > | state, |
boost::shared_ptr< ActivationModelAbstract > | activation, | ||
const VectorXs & | xref | ||
) |
Initialize the state cost model.
The default nu
value is obtained from StateAbstractTpl::get_nv()
.
[in] | state | State of the multibody system |
[in] | activation | Activation model |
[in] | xref | Reference state |
CostModelStateTpl | ( | boost::shared_ptr< typename Base::StateAbstract > | state, |
const VectorXs & | xref, | ||
const std::size_t | nu | ||
) |
Initialize the state cost model.
We use ActivationModelQuadTpl
as a default activation model (i.e. \(a=\frac{1}{2}\|\mathbf{r}\|^2\)).
[in] | state | State of the multibody system |
[in] | xref | Reference state |
[in] | nu | Dimension of the control vector |
CostModelStateTpl | ( | boost::shared_ptr< typename Base::StateAbstract > | state, |
const VectorXs & | xref | ||
) |
Initialize the state cost model.
We use ActivationModelQuadTpl
as a default activation model (i.e. \(a=\frac{1}{2}\|\mathbf{r}\|^2\)). The default nu
value is obtained from StateAbstractTpl::get_nv()
.
[in] | state | State of the multibody system |
[in] | xref | Reference state |
CostModelStateTpl | ( | boost::shared_ptr< typename Base::StateAbstract > | state, |
boost::shared_ptr< ActivationModelAbstract > | activation, | ||
const std::size_t | nu | ||
) |
Initialize the state cost model.
The default reference state is obtained from StateAbstractTpl::zero()
.
[in] | state | State of the multibody system |
[in] | activation | Activation model |
[in] | nu | Dimension of the control vector |
CostModelStateTpl | ( | boost::shared_ptr< typename Base::StateAbstract > | state, |
const std::size_t | nu | ||
) |
Initialize the state cost model.
We use ActivationModelQuadTpl
as a default activation model (i.e. \(a=\frac{1}{2}\|\mathbf{r}\|^2\)). The default reference state is obtained from StateAbstractTpl::zero()
.
[in] | state | State of the multibody system |
[in] | nu | Dimension of the control vector |
CostModelStateTpl | ( | boost::shared_ptr< typename Base::StateAbstract > | state, |
boost::shared_ptr< ActivationModelAbstract > | activation | ||
) |
Initialize the state cost model.
The default state reference is obtained from StateAbstractTpl::zero()
, and nu
from StateAbstractTpl::get_nv()
.
[in] | state | State of the multibody system |
[in] | activation | Activation model |
|
explicit |
Initialize the state cost model.
We use ActivationModelQuadTpl
as a default activation model (i.e. \(a=\frac{1}{2}\|\mathbf{r}\|^2\)). The default state reference is obtained from StateAbstractTpl::zero()
and nu
from StateAbstractTpl::get_nv()
.
[in] | state | State of the multibody system |
|
virtual |
Compute the derivatives of the state cost.
[in] | data | State cost data |
[in] | x | State point \(\mathbf{x}\in\mathbb{R}^{ndx}\) |
[in] | u | Control input \(\mathbf{u}\in\mathbb{R}^{nu}\) |
Reimplemented from CostModelResidualTpl< _Scalar >.