$search
#include <kinematic_state.h>
Public Member Functions | |
void | computeTransform (void) |
Recompute global_collision_body_transform and global_link_transform. | |
const std::vector < AttachedBodyState * > & | getAttachedBodyStateVector () const |
const btTransform & | getGlobalCollisionBodyTransform () const |
const btTransform & | getGlobalLinkTransform () const |
const KinematicModel::LinkModel * | getLinkModel () const |
const std::string & | getName () const |
const JointState * | getParentJointState () const |
const LinkState * | getParentLinkState () const |
LinkState (const KinematicModel::LinkModel *lm) | |
void | setParentJointState (const JointState *js) |
void | setParentLinkState (const LinkState *ls) |
void | updateAttachedBodies () |
void | updateGivenGlobalLinkTransform (const btTransform &transform) |
~LinkState () | |
Private Attributes | |
std::vector< AttachedBodyState * > | attached_body_state_vector_ |
btTransform | global_collision_body_transform_ |
The global transform for this link (computed by forward kinematics). | |
btTransform | global_link_transform_ |
The global transform this link forwards (computed by forward kinematics). | |
const KinematicModel::LinkModel * | link_model_ |
const JointState * | parent_joint_state_ |
const LinkState * | parent_link_state_ |
Definition at line 149 of file kinematic_state.h.
planning_models::KinematicState::LinkState::LinkState | ( | const KinematicModel::LinkModel * | lm | ) |
Definition at line 512 of file kinematic_state.cpp.
planning_models::KinematicState::LinkState::~LinkState | ( | ) |
Definition at line 527 of file kinematic_state.cpp.
void planning_models::KinematicState::LinkState::computeTransform | ( | void | ) |
Recompute global_collision_body_transform and global_link_transform.
Definition at line 534 of file kinematic_state.cpp.
const std::vector<AttachedBodyState*>& planning_models::KinematicState::LinkState::getAttachedBodyStateVector | ( | ) | const [inline] |
Definition at line 199 of file kinematic_state.h.
const btTransform& planning_models::KinematicState::LinkState::getGlobalCollisionBodyTransform | ( | ) | const [inline] |
Definition at line 209 of file kinematic_state.h.
const btTransform& planning_models::KinematicState::LinkState::getGlobalLinkTransform | ( | ) | const [inline] |
Definition at line 204 of file kinematic_state.h.
const KinematicModel::LinkModel* planning_models::KinematicState::LinkState::getLinkModel | ( | ) | const [inline] |
Definition at line 184 of file kinematic_state.h.
const std::string& planning_models::KinematicState::LinkState::getName | ( | void | ) | const [inline] |
Definition at line 156 of file kinematic_state.h.
const JointState* planning_models::KinematicState::LinkState::getParentJointState | ( | ) | const [inline] |
Definition at line 189 of file kinematic_state.h.
const LinkState* planning_models::KinematicState::LinkState::getParentLinkState | ( | ) | const [inline] |
Definition at line 194 of file kinematic_state.h.
void planning_models::KinematicState::LinkState::setParentJointState | ( | const JointState * | js | ) | [inline] |
Definition at line 161 of file kinematic_state.h.
void planning_models::KinematicState::LinkState::setParentLinkState | ( | const LinkState * | ls | ) | [inline] |
Definition at line 166 of file kinematic_state.h.
void planning_models::KinematicState::LinkState::updateAttachedBodies | ( | ) |
Definition at line 543 of file kinematic_state.cpp.
void planning_models::KinematicState::LinkState::updateGivenGlobalLinkTransform | ( | const btTransform & | transform | ) | [inline] |
Definition at line 171 of file kinematic_state.h.
std::vector<AttachedBodyState*> planning_models::KinematicState::LinkState::attached_body_state_vector_ [private] |
Definition at line 222 of file kinematic_state.h.
btTransform planning_models::KinematicState::LinkState::global_collision_body_transform_ [private] |
The global transform for this link (computed by forward kinematics).
Definition at line 228 of file kinematic_state.h.
btTransform planning_models::KinematicState::LinkState::global_link_transform_ [private] |
The global transform this link forwards (computed by forward kinematics).
Definition at line 225 of file kinematic_state.h.
Definition at line 216 of file kinematic_state.h.
Definition at line 218 of file kinematic_state.h.
const LinkState* planning_models::KinematicState::LinkState::parent_link_state_ [private] |
Definition at line 220 of file kinematic_state.h.