#include <Tasks/Tasks.h>
|
| PositionTask (const rbd::MultiBody &mb, const std::string &bodyName, const Eigen::Vector3d &pos, const Eigen::Vector3d &bodyPoint=Eigen::Vector3d::Zero()) |
|
void | position (const Eigen::Vector3d &pos) |
|
const Eigen::Vector3d & | position () const |
|
void | bodyPoint (const Eigen::Vector3d &point) |
|
const Eigen::Vector3d & | bodyPoint () const |
|
void | update (const rbd::MultiBody &mb, const rbd::MultiBodyConfig &mbc) |
|
void | update (const rbd::MultiBody &mb, const rbd::MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB) |
|
void | updateDot (const rbd::MultiBody &mb, const rbd::MultiBodyConfig &mbc) |
|
const Eigen::VectorXd & | eval () const |
|
const Eigen::VectorXd & | speed () const |
|
const Eigen::VectorXd & | normalAcc () const |
|
const Eigen::MatrixXd & | jac () const |
|
const Eigen::MatrixXd & | jacDot () const |
|
◆ PositionTask()
tasks::PositionTask::PositionTask |
( |
const rbd::MultiBody & |
mb, |
|
|
const std::string & |
bodyName, |
|
|
const Eigen::Vector3d & |
pos, |
|
|
const Eigen::Vector3d & |
bodyPoint = Eigen::Vector3d::Zero() |
|
) |
| |
◆ bodyPoint() [1/2]
const Eigen::Vector3d& tasks::PositionTask::bodyPoint |
( |
| ) |
const |
◆ bodyPoint() [2/2]
void tasks::PositionTask::bodyPoint |
( |
const Eigen::Vector3d & |
point | ) |
|
◆ eval()
const Eigen::VectorXd& tasks::PositionTask::eval |
( |
| ) |
const |
◆ jac()
const Eigen::MatrixXd& tasks::PositionTask::jac |
( |
| ) |
const |
◆ jacDot()
const Eigen::MatrixXd& tasks::PositionTask::jacDot |
( |
| ) |
const |
◆ normalAcc()
const Eigen::VectorXd& tasks::PositionTask::normalAcc |
( |
| ) |
const |
◆ position() [1/2]
const Eigen::Vector3d& tasks::PositionTask::position |
( |
| ) |
const |
◆ position() [2/2]
void tasks::PositionTask::position |
( |
const Eigen::Vector3d & |
pos | ) |
|
◆ speed()
const Eigen::VectorXd& tasks::PositionTask::speed |
( |
| ) |
const |
◆ update() [1/2]
void tasks::PositionTask::update |
( |
const rbd::MultiBody & |
mb, |
|
|
const rbd::MultiBodyConfig & |
mbc |
|
) |
| |
◆ update() [2/2]
void tasks::PositionTask::update |
( |
const rbd::MultiBody & |
mb, |
|
|
const rbd::MultiBodyConfig & |
mbc, |
|
|
const std::vector< sva::MotionVecd > & |
normalAccB |
|
) |
| |
◆ updateDot()
void tasks::PositionTask::updateDot |
( |
const rbd::MultiBody & |
mb, |
|
|
const rbd::MultiBodyConfig & |
mbc |
|
) |
| |
The documentation for this class was generated from the following file: