planning_models::KinematicState::LinkState Class Reference

#include <kinematic_state.h>

List of all members.

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::LinkModelgetLinkModel () const
const std::string & getName () const
const JointStategetParentJointState () const
const LinkStategetParentLinkState () 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::LinkModellink_model_
const JointStateparent_joint_state_
const LinkStateparent_link_state_

Detailed Description

Definition at line 145 of file kinematic_state.h.


Constructor & Destructor Documentation

planning_models::KinematicState::LinkState::LinkState ( const KinematicModel::LinkModel lm  ) 

Definition at line 461 of file kinematic_state.cpp.

planning_models::KinematicState::LinkState::~LinkState (  ) 

Definition at line 476 of file kinematic_state.cpp.


Member Function Documentation

void planning_models::KinematicState::LinkState::computeTransform ( void   ) 

Recompute global_collision_body_transform and global_link_transform.

Definition at line 483 of file kinematic_state.cpp.

const std::vector<AttachedBodyState*>& planning_models::KinematicState::LinkState::getAttachedBodyStateVector (  )  const [inline]

Definition at line 195 of file kinematic_state.h.

const btTransform& planning_models::KinematicState::LinkState::getGlobalCollisionBodyTransform (  )  const [inline]

Definition at line 205 of file kinematic_state.h.

const btTransform& planning_models::KinematicState::LinkState::getGlobalLinkTransform (  )  const [inline]

Definition at line 200 of file kinematic_state.h.

const KinematicModel::LinkModel* planning_models::KinematicState::LinkState::getLinkModel (  )  const [inline]

Definition at line 180 of file kinematic_state.h.

const std::string& planning_models::KinematicState::LinkState::getName ( void   )  const [inline]

Definition at line 152 of file kinematic_state.h.

const JointState* planning_models::KinematicState::LinkState::getParentJointState (  )  const [inline]

Definition at line 185 of file kinematic_state.h.

const LinkState* planning_models::KinematicState::LinkState::getParentLinkState (  )  const [inline]

Definition at line 190 of file kinematic_state.h.

void planning_models::KinematicState::LinkState::setParentJointState ( const JointState js  )  [inline]

Definition at line 157 of file kinematic_state.h.

void planning_models::KinematicState::LinkState::setParentLinkState ( const LinkState ls  )  [inline]

Definition at line 162 of file kinematic_state.h.

void planning_models::KinematicState::LinkState::updateAttachedBodies (  ) 

Definition at line 492 of file kinematic_state.cpp.

void planning_models::KinematicState::LinkState::updateGivenGlobalLinkTransform ( const btTransform &  transform  )  [inline]

Definition at line 167 of file kinematic_state.h.


Member Data Documentation

Definition at line 218 of file kinematic_state.h.

The global transform for this link (computed by forward kinematics).

Definition at line 224 of file kinematic_state.h.

The global transform this link forwards (computed by forward kinematics).

Definition at line 221 of file kinematic_state.h.

Definition at line 212 of file kinematic_state.h.

Definition at line 214 of file kinematic_state.h.

Definition at line 216 of file kinematic_state.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Friends


planning_models
Author(s): Ioan Sucan/isucan@willowgarage.com
autogenerated on Fri Jan 11 09:14:26 2013