|
| 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, boost::shared_ptr< ActivationModelAbstract > activation, 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...
|
|
| CostModelFrameRotationTpl (boost::shared_ptr< StateMultibody > state, const FrameRotation &Fref) |
| 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 set_reference<FrameRotationTpl<Scalar> >()", void set_Rref(const FrameRotation &Rref_in)) |
|
| DEPRECATED ("Use get_reference<FrameRotationTpl<Scalar> >()", const FrameRotation &get_Rref() const) |
|
| 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< ActivationModelAbstract > activation) |
|
| CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t &nr, const std::size_t &nu) |
|
| CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t &nr) |
|
virtual void | calc (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)=0 |
| Compute the cost value and its residual vector. More...
|
|
void | calc (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) |
|
virtual void | calcDiff (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)=0 |
| Compute the Jacobian and Hessian of cost and its residual vector. More...
|
|
void | calcDiff (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) |
|
const boost::shared_ptr< ActivationModelAbstract > & | get_activation () const |
| Return the activation model.
|
|
const 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.
|
|
template<typename _Scalar>
class crocoddyl::CostModelFrameRotationTpl< _Scalar >
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.
- See also
CostModelAbstractTpl
, calc()
, calcDiff()
, createData()
Definition at line 39 of file frame-rotation.hpp.