#include <kinematic_state.h>
Public Member Functions | |
AttachedBodyState (const KinematicModel::AttachedBodyModel *abm, const LinkState *parent_link_state) | |
void | computeTransform (void) |
Recompute global_collision_body_transform. | |
const KinematicModel::AttachedBodyModel * | getAttachedBodyModel () const |
const std::string & | getAttachedLinkName () const |
const std::vector < tf::Transform > & | getGlobalCollisionBodyTransforms () const |
const std::string & | getName () const |
~AttachedBodyState () | |
Private Attributes | |
const KinematicModel::AttachedBodyModel * | attached_body_model_ |
std::vector< tf::Transform > | global_collision_body_transforms_ |
The global transforms for these attached bodies (computed by forward kinematics) | |
const LinkState * | parent_link_state_ |
Definition at line 240 of file kinematic_state.h.
planning_models::KinematicState::AttachedBodyState::AttachedBodyState | ( | const KinematicModel::AttachedBodyModel * | abm, |
const LinkState * | parent_link_state | ||
) |
Definition at line 553 of file kinematic_state.cpp.
Definition at line 245 of file kinematic_state.h.
Recompute global_collision_body_transform.
Definition at line 564 of file kinematic_state.cpp.
const KinematicModel::AttachedBodyModel* planning_models::KinematicState::AttachedBodyState::getAttachedBodyModel | ( | ) | const [inline] |
Definition at line 259 of file kinematic_state.h.
const std::string& planning_models::KinematicState::AttachedBodyState::getAttachedLinkName | ( | ) | const [inline] |
Definition at line 254 of file kinematic_state.h.
const std::vector<tf::Transform>& planning_models::KinematicState::AttachedBodyState::getGlobalCollisionBodyTransforms | ( | ) | const [inline] |
Definition at line 267 of file kinematic_state.h.
const std::string& planning_models::KinematicState::AttachedBodyState::getName | ( | void | ) | const [inline] |
Definition at line 249 of file kinematic_state.h.
const KinematicModel::AttachedBodyModel* planning_models::KinematicState::AttachedBodyState::attached_body_model_ [private] |
Definition at line 273 of file kinematic_state.h.
std::vector<tf::Transform> planning_models::KinematicState::AttachedBodyState::global_collision_body_transforms_ [private] |
The global transforms for these attached bodies (computed by forward kinematics)
Definition at line 278 of file kinematic_state.h.
Definition at line 275 of file kinematic_state.h.