Frame translation cost. More...
#include <crocoddyl/multibody/costs/frame-translation.hpp>
Public Types | |
typedef ActivationModelAbstractTpl< Scalar > | ActivationModelAbstract |
typedef CostModelResidualTpl< Scalar > | Base |
typedef FrameTranslationTpl< Scalar > | FrameTranslation |
typedef MathBaseTpl< Scalar > | MathBase |
typedef MathBase::Matrix3xs | Matrix3xs |
typedef ResidualModelFrameTranslationTpl< Scalar > | ResidualModelFrameTranslation |
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 | |
CostModelFrameTranslationTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FrameTranslation &xref) | |
Initialize the frame translation cost model. More... | |
CostModelFrameTranslationTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FrameTranslation &xref, const std::size_t nu) | |
Initialize the frame translation cost model. More... | |
CostModelFrameTranslationTpl (boost::shared_ptr< StateMultibody > state, const FrameTranslation &xref) | |
Initialize the frame translation cost model. More... | |
CostModelFrameTranslationTpl (boost::shared_ptr< StateMultibody > state, const FrameTranslation &xref, const std::size_t nu) | |
Initialize the frame translation cost model. 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 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 residual cost. 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 frame translation reference. | |
virtual void | set_referenceImpl (const std::type_info &ti, const void *pv) |
Modify the frame translation 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. | |
Frame translation cost.
This cost function defines a residual vector as \(\mathbf{r}=\mathbf{t}-\mathbf{t}^*\), where \(\mathbf{t},\mathbf{t}^*\in~\mathbb{R}^3\) are the current and reference frame translations, respectively. Note that the dimension of the residual vector is 3.
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_{xu}} = \mathbf{l_{x}}^T \mathbf{l_{u}} \).
As described in CostModelResidualTpl()
, the cost value and its derivatives are calculated by calc
and calcDiff
, respectively.
CostModelResidualTpl
, calc()
, calcDiff()
, createData()
Definition at line 42 of file frame-translation.hpp.
CostModelFrameTranslationTpl | ( | boost::shared_ptr< StateMultibody > | state, |
boost::shared_ptr< ActivationModelAbstract > | activation, | ||
const FrameTranslation & | xref, | ||
const std::size_t | nu | ||
) |
Initialize the frame translation cost model.
[in] | state | State of the multibody system |
[in] | activation | Activation model |
[in] | xref | Reference frame translation |
[in] | nu | Dimension of the control vector |
CostModelFrameTranslationTpl | ( | boost::shared_ptr< StateMultibody > | state, |
boost::shared_ptr< ActivationModelAbstract > | activation, | ||
const FrameTranslation & | xref | ||
) |
Initialize the frame translation cost model.
The default nu
is equals to StateAbstractTpl::get_nv().
[in] | state | State of the multibody system |
[in] | activation | Activation model |
[in] | xref | Reference frame translation |
CostModelFrameTranslationTpl | ( | boost::shared_ptr< StateMultibody > | state, |
const FrameTranslation & | xref, | ||
const std::size_t | nu | ||
) |
Initialize the frame translation 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 frame translation |
[in] | nu | Dimension of the control vector |
CostModelFrameTranslationTpl | ( | boost::shared_ptr< StateMultibody > | state, |
const FrameTranslation & | xref | ||
) |
Initialize the frame translation cost model.
We use ActivationModelQuadTpl
as a default activation model (i.e. \(a=\frac{1}{2}\|\mathbf{r}\|^2\)). Furthermore, the default nu
is equals to StateAbstractTpl::get_nv()
[in] | state | State of the multibody system |
[in] | xref | Reference frame translation |