#include <Tasks/Tasks.h>
|
typedef std::tuple< std::string, Eigen::Vector3d, Eigen::Vector3d > | rbInfo |
|
|
| RelativeDistTask (const rbd::MultiBody &mb, const double timestep, const rbInfo &rbi1, const rbInfo &rbi2, const Eigen::Vector3d &u1=Eigen::Vector3d::Zero(), const Eigen::Vector3d &u2=Eigen::Vector3d::Zero()) |
|
void | robotPoint (const int bIndex, const Eigen::Vector3d &point) |
|
void | envPoint (const int bIndex, const Eigen::Vector3d &point) |
|
void | vector (const int bIndex, const Eigen::Vector3d &u) |
|
void | update (const rbd::MultiBody &mb, const rbd::MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB) |
|
const Eigen::VectorXd & | eval () const |
|
const Eigen::VectorXd & | speed () const |
|
const Eigen::VectorXd & | normalAcc () const |
|
const Eigen::MatrixXd & | jac () const |
|
◆ rbInfo
◆ RelativeDistTask()
tasks::RelativeDistTask::RelativeDistTask |
( |
const rbd::MultiBody & |
mb, |
|
|
const double |
timestep, |
|
|
const rbInfo & |
rbi1, |
|
|
const rbInfo & |
rbi2, |
|
|
const Eigen::Vector3d & |
u1 = Eigen::Vector3d::Zero() , |
|
|
const Eigen::Vector3d & |
u2 = Eigen::Vector3d::Zero() |
|
) |
| |
◆ envPoint()
void tasks::RelativeDistTask::envPoint |
( |
const int |
bIndex, |
|
|
const Eigen::Vector3d & |
point |
|
) |
| |
◆ eval()
const Eigen::VectorXd& tasks::RelativeDistTask::eval |
( |
| ) |
const |
◆ jac()
const Eigen::MatrixXd& tasks::RelativeDistTask::jac |
( |
| ) |
const |
◆ normalAcc()
const Eigen::VectorXd& tasks::RelativeDistTask::normalAcc |
( |
| ) |
const |
◆ robotPoint()
void tasks::RelativeDistTask::robotPoint |
( |
const int |
bIndex, |
|
|
const Eigen::Vector3d & |
point |
|
) |
| |
◆ speed()
const Eigen::VectorXd& tasks::RelativeDistTask::speed |
( |
| ) |
const |
◆ update()
void tasks::RelativeDistTask::update |
( |
const rbd::MultiBody & |
mb, |
|
|
const rbd::MultiBodyConfig & |
mbc, |
|
|
const std::vector< sva::MotionVecd > & |
normalAccB |
|
) |
| |
◆ vector()
void tasks::RelativeDistTask::vector |
( |
const int |
bIndex, |
|
|
const Eigen::Vector3d & |
u |
|
) |
| |
The documentation for this class was generated from the following file: