Frame velocity residual. More...
#include <frame-velocity.hpp>
Public Types | |
typedef ResidualModelAbstractTpl< Scalar > | Base |
typedef ResidualDataFrameVelocityTpl< Scalar > | Data |
typedef DataCollectorAbstractTpl< Scalar > | DataCollectorAbstract |
typedef MathBaseTpl< Scalar > | MathBase |
typedef pinocchio::MotionTpl< Scalar > | Motion |
typedef ResidualDataAbstractTpl< Scalar > | ResidualDataAbstract |
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 | |
ResidualModelFrameVelocityTpl (std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Motion &velocity, const pinocchio::ReferenceFrame type) | |
Initialize the frame velocity residual model. | |
ResidualModelFrameVelocityTpl (std::shared_ptr< StateMultibody > state, const pinocchio::FrameIndex id, const Motion &velocity, const pinocchio::ReferenceFrame type, const std::size_t nu) | |
Initialize the frame velocity 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 velocity residual vector. | |
virtual void | calcDiff (const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) |
Compute the Jacobians of the frame velocity residual. | |
virtual std::shared_ptr< ResidualDataAbstract > | createData (DataCollectorAbstract *const data) |
Create the frame velocity residual data. | |
pinocchio::FrameIndex | get_id () const |
Return the reference frame id. | |
const Motion & | get_reference () const |
Return the reference velocity. | |
pinocchio::ReferenceFrame | get_type () const |
Return the reference type of velocity. | |
virtual void | print (std::ostream &os) const |
Print relevant information of the frame-velocity residual. | |
void | set_id (const pinocchio::FrameIndex id) |
Modify reference frame id. | |
void | set_reference (const Motion &velocity) |
Modify reference velocity. | |
void | set_type (const pinocchio::ReferenceFrame type) |
Modify reference type of velocity. | |
![]() | |
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 | nr_ |
Residual vector dimension. | |
std::size_t | nu_ |
Control dimension. | |
std::shared_ptr< StateAbstract > | state_ |
State description. | |
bool | u_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 velocity residual.
This residual function defines a tracking of frame velocity as \(\mathbf{r}=\mathbf{v}-\mathbf{v}^*\), where \(\mathbf{v},\mathbf{v}^*\in~T_{\mathbf{p}}~\mathbb{SE(3)}\) are the current and reference frame velocities, respectively. Note that the tangent vector is described by the frame placement \(\mathbf{p}\), and the dimension of the residual vector is 6. Furthermore, the Jacobians of the residual function are computed analytically.
As described in ResidualModelAbstractTpl
, the residual vector and its Jacobians are calculated by calc
and calcDiff
, respectively.
ResidualModelAbstractTpl
, calc()
, calcDiff()
, createData()
Definition at line 40 of file frame-velocity.hpp.
typedef MathBaseTpl<Scalar> MathBase |
Definition at line 45 of file frame-velocity.hpp.
typedef ResidualModelAbstractTpl<Scalar> Base |
Definition at line 46 of file frame-velocity.hpp.
typedef ResidualDataFrameVelocityTpl<Scalar> Data |
Definition at line 47 of file frame-velocity.hpp.
typedef StateMultibodyTpl<Scalar> StateMultibody |
Definition at line 48 of file frame-velocity.hpp.
typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract |
Definition at line 49 of file frame-velocity.hpp.
typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract |
Definition at line 50 of file frame-velocity.hpp.
typedef pinocchio::MotionTpl<Scalar> Motion |
Definition at line 51 of file frame-velocity.hpp.
typedef MathBase::VectorXs VectorXs |
Definition at line 52 of file frame-velocity.hpp.
ResidualModelFrameVelocityTpl | ( | std::shared_ptr< StateMultibody > | state, |
const pinocchio::FrameIndex | id, | ||
const Motion & | velocity, | ||
const pinocchio::ReferenceFrame | type, | ||
const std::size_t | nu | ||
) |
Initialize the frame velocity residual model.
[in] | state | State of the multibody system |
[in] | id | Reference frame id |
[in] | velocity | Reference velocity |
[in] | type | Reference type of velocity (WORLD, LOCAL, LOCAL_WORLD_ALIGNED) |
[in] | nu | Dimension of the control vector |
ResidualModelFrameVelocityTpl | ( | std::shared_ptr< StateMultibody > | state, |
const pinocchio::FrameIndex | id, | ||
const Motion & | velocity, | ||
const pinocchio::ReferenceFrame | type | ||
) |
Initialize the frame velocity residual model.
The default nu
value is obtained from StateAbstractTpl::get_nv()
.
[in] | state | State of the multibody system |
[in] | id | Reference frame id |
[in] | velocity | Reference velocity |
[in] | type | Reference type of velocity (WORLD, LOCAL, LOCAL_WORLD_ALIGNED) |
|
virtual |
Compute the frame velocity residual vector.
[in] | data | Frame velocity 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 Jacobians of the frame velocity residual.
[in] | data | Frame velocity 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 velocity residual data.
Reimplemented from ResidualModelAbstractTpl< _Scalar >.
|
virtual |
Print relevant information of the frame-velocity 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-velocity.hpp.
|
protected |
Residual vector dimension.
Definition at line 226 of file residual-base.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.