Frame placement residual. More...
#include <crocoddyl/multibody/residuals/frame-placement.hpp>
Public Types | |
typedef ResidualModelAbstractTpl< Scalar > | Base |
typedef ResidualDataFramePlacementTpl< Scalar > | Data |
typedef DataCollectorAbstractTpl< Scalar > | DataCollectorAbstract |
typedef MathBaseTpl< Scalar > | MathBase |
typedef ResidualDataAbstractTpl< Scalar > | ResidualDataAbstract |
typedef pinocchio::SE3Tpl< Scalar > | SE3 |
typedef StateMultibodyTpl< Scalar > | StateMultibody |
typedef MathBase::VectorXs | VectorXs |
Public Member Functions | |
ResidualModelFramePlacementTpl (boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const SE3 &pref) | |
Initialize the frame placement residual model. More... | |
ResidualModelFramePlacementTpl (boost::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const SE3 &pref, const std::size_t nu) | |
Initialize the frame placement residual model. More... | |
virtual void | calc (const boost::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) |
Compute the frame placement residual. More... | |
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 frame placement residual. More... | |
virtual boost::shared_ptr< ResidualDataAbstract > | createData (DataCollectorAbstract *const data) |
Create the frame placement residual data. | |
pinocchio::FrameIndex | get_id () const |
Return the reference frame id. | |
const SE3 & | get_reference () const |
Return the reference frame placement. | |
virtual void | print (std::ostream &os) const |
Print relevant information of the frame-placement residual. More... | |
void | set_id (const pinocchio::FrameIndex id) |
Modify the reference frame id. | |
void | set_reference (const SE3 &reference) |
Modify the reference frame placement. | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
Protected Attributes | |
std::size_t | nu_ |
Control dimension. | |
boost::shared_ptr< StateAbstract > | state_ |
State description. | |
bool | u_dependent_ |
Label that indicates if the residual function depends on u. | |
VectorXs | unone_ |
No control vector. | |
bool | v_dependent_ |
Label that indicates if the residual function depends on v. | |
Frame placement residual.
This residual function defines the frame placement tracking as \(\mathbf{r}=\mathbf{p}\ominus\mathbf{p}^*\), where \(\mathbf{p},\mathbf{p}^*\in~\mathbb{SE(3)}\) are the current and reference frame placements, respectively. Note that the dimension of the residual vector is 6. Furthermore, the Jacobians of the residual function are computed analytically.
As described in ResidualModelAbstractTpl()
, the residual value and its Jacobians are calculated by calc
and calcDiff
, respectively.
ResidualModelAbstractTpl
, calc()
, calcDiff()
, createData()
ResidualModelFramePlacementTpl | ( | boost::shared_ptr< StateMultibody > | state, |
const pinocchio::FrameIndex | id, | ||
const SE3 & | pref, | ||
const std::size_t | nu | ||
) |
Initialize the frame placement residual model.
[in] | state | State of the multibody system |
[in] | id | Reference frame id |
[in] | pref | Reference frame placement |
[in] | nu | Dimension of the control vector |
ResidualModelFramePlacementTpl | ( | boost::shared_ptr< StateMultibody > | state, |
const pinocchio::FrameIndex | id, | ||
const SE3 & | pref | ||
) |
Initialize the frame placement residual model.
The default nu
is obtained from StateAbstractTpl::get_nv()
.
[in] | state | State of the multibody system |
[in] | id | Reference frame id |
[in] | pref | Reference frame placement |
|
virtual |
Compute the frame placement residual.
[in] | data | Frame placement residual data |
[in] | x | State point \(\mathbf{x}\in\mathbb{R}^{ndx}\) |
[in] | u | Control input \(\mathbf{u}\in\mathbb{R}^{nu}\) |
|
virtual |
Compute the derivatives of the frame placement residual.
[in] | data | Frame-placement residual data |
[in] | x | State point \(\mathbf{x}\in\mathbb{R}^{ndx}\) |
[in] | u | Control input \(\mathbf{u}\in\mathbb{R}^{nu}\) |
|
virtual |
Print relevant information of the frame-placement residual.
[out] | os | Output stream object |