tasks::TransformTask Class Reference

#include <Tasks/Tasks.h>

Inheritance diagram for tasks::TransformTask:
Collaboration diagram for tasks::TransformTask:

Public Member Functions

 TransformTask (const rbd::MultiBody &mb, const std::string &bodyName, const sva::PTransformd &X_0_t, const sva::PTransformd &X_b_p=sva::PTransformd::Identity(), const Eigen::Matrix3d &E_0_c=Eigen::Matrix3d::Identity())
 
void E_0_c (const Eigen::Matrix3d &E_0_c)
 
const Eigen::Matrix3d & E_0_c () const
 
void update (const rbd::MultiBody &mb, const rbd::MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB)
 
- Public Member Functions inherited from tasks::TransformTaskCommon
 TransformTaskCommon (const rbd::MultiBody &mb, const std::string &bodyName, const sva::PTransformd &X_0_t, const sva::PTransformd &X_b_p)
 
void target (const sva::PTransformd &X_0_t)
 
const sva::PTransformd & target () const
 
void X_b_p (const sva::PTransformd &X_b_p)
 
const sva::PTransformd & X_b_p () const
 
const Eigen::VectorXd & eval () const
 
const Eigen::VectorXd & speed () const
 
const Eigen::VectorXd & normalAcc () const
 
const Eigen::MatrixXd & jac () const
 

Additional Inherited Members

- Protected Attributes inherited from tasks::TransformTaskCommon
sva::PTransformd X_0_t_
 
sva::PTransformd X_b_p_
 
int bodyIndex_
 
rbd::Jacobian jac_
 
Eigen::VectorXd eval_
 
Eigen::VectorXd speed_
 
Eigen::VectorXd normalAcc_
 
Eigen::MatrixXd jacMat_
 

Constructor & Destructor Documentation

◆ TransformTask()

tasks::TransformTask::TransformTask ( const rbd::MultiBody &  mb,
const std::string &  bodyName,
const sva::PTransformd &  X_0_t,
const sva::PTransformd &  X_b_p = sva::PTransformd::Identity(),
const Eigen::Matrix3d &  E_0_c = Eigen::Matrix3d::Identity() 
)

Compute eval, speed, normalAcc and jac in the world frame (0) or in the user defined static frame 'c'.

Parameters
E_0_cOptional rotation between the world farme and a user defined frame 'c' to change the frame of the task.

Member Function Documentation

◆ E_0_c() [1/2]

const Eigen::Matrix3d& tasks::TransformTask::E_0_c ( ) const

◆ E_0_c() [2/2]

void tasks::TransformTask::E_0_c ( const Eigen::Matrix3d &  E_0_c)

◆ update()

void tasks::TransformTask::update ( const rbd::MultiBody &  mb,
const rbd::MultiBodyConfig &  mbc,
const std::vector< sva::MotionVecd > &  normalAccB 
)

The documentation for this class was generated from the following file: