Frame placement residual. More...
#include <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 |
![]() | |
typedef ActivationDataAbstractTpl< Scalar > | ActivationDataAbstract |
typedef CostDataAbstractTpl< Scalar > | CostDataAbstract |
typedef DataCollectorAbstractTpl< Scalar > | DataCollectorAbstract |
typedef MathBase::DiagonalMatrixXs | DiagonalMatrixXs |
typedef MathBaseTpl< Scalar > | MathBase |
typedef MathBase::MatrixXs | MatrixXs |
typedef ResidualDataAbstractTpl< Scalar > | ResidualDataAbstract |
typedef StateAbstractTpl< Scalar > | StateAbstract |
typedef MathBase::VectorXs | VectorXs |
Public Member Functions | |
ResidualModelFramePlacementTpl (std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const SE3 &pref) | |
Initialize the frame placement residual model. | |
ResidualModelFramePlacementTpl (std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const SE3 &pref, const std::size_t nu) | |
Initialize the frame placement residual model. | |
virtual void | calc (const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) |
Compute the frame placement residual. | |
virtual void | calcDiff (const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) |
Compute the derivatives of the frame placement residual. | |
virtual std::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. | |
void | set_id (const pinocchio::FrameIndex id) |
Modify the reference frame id. | |
void | set_reference (const SE3 &reference) |
Modify the reference frame placement. | |
![]() | |
ResidualModelAbstractTpl (std::shared_ptr< StateAbstract > state, const std::size_t nr, const bool q_dependent=true, const bool v_dependent=true, const bool u_dependent=true) | |
ResidualModelAbstractTpl (std::shared_ptr< StateAbstract > state, const std::size_t nr, const std::size_t nu, const bool q_dependent=true, const bool v_dependent=true, const bool u_dependent=true) | |
Initialize the residual model. | |
virtual void | calc (const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) |
Compute the residual vector for nodes that depends only on the state. | |
virtual void | calcCostDiff (const std::shared_ptr< CostDataAbstract > &cdata, const std::shared_ptr< ResidualDataAbstract > &rdata, const std::shared_ptr< ActivationDataAbstract > &adata, const bool update_u=true) |
Compute the derivative of the cost function. | |
virtual void | calcDiff (const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) |
Compute the Jacobian of the residual functions with respect to the state only. | |
std::size_t | get_nr () const |
Return the dimension of the residual vector. | |
std::size_t | get_nu () const |
Return the dimension of the control input. | |
bool | get_q_dependent () const |
Return true if the residual function depends on q. | |
const std::shared_ptr< StateAbstract > & | get_state () const |
Return the state. | |
bool | get_u_dependent () const |
Return true if the residual function depends on u. | |
bool | get_v_dependent () const |
Return true if the residual function depends on v. | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
![]() | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
Protected Attributes | |
std::size_t | nu_ |
Control dimension. | |
std::shared_ptr< StateAbstract > | state_ |
State description. | |
bool | u_dependent_ |
bool | v_dependent_ |
![]() | |
std::size_t | nr_ |
Residual vector dimension. | |
std::size_t | nu_ |
Control dimension. | |
bool | q_dependent_ |
std::shared_ptr< StateAbstract > | state_ |
State description. | |
bool | u_dependent_ |
VectorXs | unone_ |
No control vector. | |
bool | v_dependent_ |
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()
Definition at line 39 of file frame-placement.hpp.
typedef MathBaseTpl<Scalar> MathBase |
Definition at line 45 of file frame-placement.hpp.
typedef ResidualModelAbstractTpl<Scalar> Base |
Definition at line 46 of file frame-placement.hpp.
typedef ResidualDataFramePlacementTpl<Scalar> Data |
Definition at line 47 of file frame-placement.hpp.
typedef StateMultibodyTpl<Scalar> StateMultibody |
Definition at line 48 of file frame-placement.hpp.
typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract |
Definition at line 49 of file frame-placement.hpp.
typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract |
Definition at line 50 of file frame-placement.hpp.
typedef MathBase::VectorXs VectorXs |
Definition at line 51 of file frame-placement.hpp.
typedef pinocchio::SE3Tpl<Scalar> SE3 |
Definition at line 52 of file frame-placement.hpp.
ResidualModelFramePlacementTpl | ( | std::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 | ( | std::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}\) |
Reimplemented from ResidualModelAbstractTpl< _Scalar >.
|
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}\) |
Reimplemented from ResidualModelAbstractTpl< _Scalar >.
|
virtual |
Create the frame placement residual data.
Reimplemented from ResidualModelAbstractTpl< _Scalar >.
|
virtual |
Print relevant information of the frame-placement residual.
[out] | os | Output stream object |
Reimplemented from ResidualModelAbstractTpl< _Scalar >.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar |
Definition at line 44 of file frame-placement.hpp.
|
protected |
Control dimension.
Definition at line 227 of file residual-base.hpp.
|
protected |
State description.
Definition at line 225 of file residual-base.hpp.
|
protected |
Label that indicates if the residual function depends on u
Definition at line 233 of file residual-base.hpp.
|
protected |
Label that indicates if the residual function depends on v
Definition at line 231 of file residual-base.hpp.