Frame rotation cost. More...
#include <crocoddyl/multibody/costs/frame-rotation.hpp>
Public Types | |
typedef ActivationModelAbstractTpl< Scalar > | ActivationModelAbstract |
typedef CostModelAbstractTpl< Scalar > | Base |
typedef CostDataAbstractTpl< Scalar > | CostDataAbstract |
typedef CostDataFrameRotationTpl< Scalar > | Data |
typedef DataCollectorAbstractTpl< Scalar > | DataCollectorAbstract |
typedef FrameRotationTpl< Scalar > | FrameRotation |
typedef MathBaseTpl< Scalar > | MathBase |
typedef MathBase::Matrix3s | Matrix3s |
typedef StateMultibodyTpl< Scalar > | StateMultibody |
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 StateAbstractTpl< Scalar > | StateAbstract |
typedef MathBase::VectorXs | VectorXs |
Public Member Functions | |
CostModelFrameRotationTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FrameRotation &Fref) | |
Initialize the frame rotation cost model. More... | |
CostModelFrameRotationTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FrameRotation &Fref, const std::size_t nu) | |
Initialize the frame rotation cost model. More... | |
CostModelFrameRotationTpl (boost::shared_ptr< StateMultibody > state, const FrameRotation &Fref) | |
Initialize the frame rotation cost model. More... | |
CostModelFrameRotationTpl (boost::shared_ptr< StateMultibody > state, const FrameRotation &Fref, const std::size_t nu) | |
Initialize the frame rotation cost model. More... | |
virtual void | calc (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) |
Compute the frame rotation cost. 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 frame rotation cost. More... | |
virtual boost::shared_ptr< CostDataAbstract > | createData (DataCollectorAbstract *const data) |
Create the frame rotation cost data. | |
DEPRECATED ("Use get_reference<FrameRotationTpl<Scalar> >()", const FrameRotation &get_Rref() const) | |
DEPRECATED ("Use set_reference<FrameRotationTpl<Scalar> >()", void set_Rref(const FrameRotation &Rref_in)) | |
![]() | |
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, const std::size_t nu) | |
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... | |
void | calc (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) |
Compute the cost value and its residual vector. More... | |
void | calcDiff (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) |
Compute the Jacobian and Hessian of cost and its residual vector. 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 () const |
Return the cost reference. | |
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 |
Protected Member Functions | |
virtual void | get_referenceImpl (const std::type_info &ti, void *pv) const |
Return the frame rotation reference. | |
virtual void | set_referenceImpl (const std::type_info &ti, const void *pv) |
Modify the frame rotation reference. | |
Protected Attributes | |
boost::shared_ptr< ActivationModelAbstract > | activation_ |
Activation model. | |
std::size_t | nu_ |
Control dimension. | |
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< StateAbstract > | state_ |
State description. | |
VectorXs | unone_ |
No control vector. | |
Frame rotation cost.
This cost function defines a residual vector as \(\mathbf{r}=\mathbf{R}\ominus\mathbf{R}^*\), where \(\mathbf{R},\mathbf{R}^*\in~\mathbb{SO(3)}\) are the current and reference frame rotations, 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 CostModelAbstractTpl(), the cost value and its derivatives are calculated by calc
and calcDiff
, respectively.
CostModelAbstractTpl
, calc()
, calcDiff()
, createData()
Definition at line 39 of file frame-rotation.hpp.
CostModelFrameRotationTpl | ( | boost::shared_ptr< StateMultibody > | state, |
boost::shared_ptr< ActivationModelAbstract > | activation, | ||
const FrameRotation & | Fref, | ||
const std::size_t | nu | ||
) |
Initialize the frame rotation cost model.
[in] | state | State of the multibody system |
[in] | activation | Activation model |
[in] | Fref | Reference frame rotation |
[in] | nu | Dimension of the control vector |
CostModelFrameRotationTpl | ( | boost::shared_ptr< StateMultibody > | state, |
boost::shared_ptr< ActivationModelAbstract > | activation, | ||
const FrameRotation & | Fref | ||
) |
Initialize the frame rotation cost model.
The default nu
is equals to StateAbstractTpl::get_nv().
[in] | state | State of the multibody system |
[in] | activation | Activation model |
[in] | Fref | Reference frame rotation |
[in] | nu | Dimension of the control vector |
CostModelFrameRotationTpl | ( | boost::shared_ptr< StateMultibody > | state, |
const FrameRotation & | Fref, | ||
const std::size_t | nu | ||
) |
Initialize the frame rotation 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] | activation | Activation model |
[in] | Fref | Reference frame rotation |
[in] | nu | Dimension of the control vector |
CostModelFrameRotationTpl | ( | boost::shared_ptr< StateMultibody > | state, |
const FrameRotation & | Fref | ||
) |
Initialize the frame rotation 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] | activation | Activation model |
[in] | Fref | Reference frame rotation |
[in] | nu | Dimension of the control vector |
|
virtual |
Compute the frame rotation cost.
[in] | data | Frame rotation cost data |
[in] | x | State point \(\mathbf{x}\in\mathbb{R}^{ndx}\) |
[in] | u | Control input \(\mathbf{u}\in\mathbb{R}^{nu}\) |
Implements CostModelAbstractTpl< _Scalar >.
|
virtual |
Compute the derivatives of the frame rotation cost.
[in] | data | Frame rotation cost data |
[in] | x | State point \(\mathbf{x}\in\mathbb{R}^{ndx}\) |
[in] | u | Control input \(\mathbf{u}\in\mathbb{R}^{nu}\) |
Implements CostModelAbstractTpl< _Scalar >.