planning_models::KinematicState Class Reference

Definition of a kinematic state - the parts of the robot state which can change. It is not thread safe, however multiple instances can be created. More...

#include <kinematic_state.h>

List of all members.

Classes

class  AttachedBodyState
class  JointState
 Forward definition of a joint group state. More...
class  JointStateGroup
class  LinkState

Public Member Functions

bool areJointsWithinBounds (const std::vector< std::string > &joints) const
AttachedBodyStategetAttachedBodyState (const std::string &attached) const
 Get an attached body state by its name.
const std::vector< const
AttachedBodyState * > & 
getAttachedBodyStateVector () const
std::vector< LinkState * > getChildLinkStates (const std::string &link_name) const
unsigned int getDimension () const
JointStategetJointState (const std::string &joint) const
 Get a joint state by its name.
JointStateGroupgetJointStateGroup (const std::string &name)
 Get a group by its name.
const JointStateGroupgetJointStateGroup (const std::string &name) const
 Get a group by its name.
const std::map< std::string,
JointStateGroup * > & 
getJointStateGroupMap () const
void getJointStateGroupNames (std::vector< std::string > &names) const
std::vector< JointState * > & getJointStateVector ()
const std::vector< JointState * > & getJointStateVector () const
const boost::shared_ptr< const
KinematicModel
getKinematicModel () const
const std::map< std::string,
unsigned int > 
getKinematicStateIndexMap () const
void getKinematicStateValues (std::map< std::string, double > &joint_state_values) const
void getKinematicStateValues (std::vector< double > &joint_state_values) const
LinkStategetLinkState (const std::string &link) const
 Get a link state by its name.
const std::vector< LinkState * > & getLinkStateVector () const
bool hasJointState (const std::string &joint) const
 Check if a joint is part of this state.
bool hasJointStateGroup (const std::string &name) const
 Check if a group exists.
bool hasLinkState (const std::string &joint) const
 Check if a link is updated by this state.
bool isJointWithinBounds (const std::string &joint) const
 KinematicState (const KinematicState *state)
 KinematicState (const boost::shared_ptr< const KinematicModel > kinematic_model)
void printStateInfo (std::ostream &out=std::cout) const
 Print information about the constructed model.
void printTransform (const std::string &st, const btTransform &t, std::ostream &out=std::cout) const
void printTransforms (std::ostream &out=std::cout) const
 Print the pose of every link.
bool setKinematicState (const std::map< std::string, double > &joint_state_map)
bool setKinematicState (const std::vector< double > &joint_state_values)
void setKinematicStateToDefault ()
void updateKinematicLinks ()
bool updateKinematicStateWithLinkAt (const std::string &link_name, const btTransform &transform)
 ~KinematicState (void)

Private Member Functions

void setLinkStatesParents ()

Private Attributes

std::vector< const
AttachedBodyState * > 
attached_body_state_vector_
unsigned int dimension_
std::map< std::string,
JointStateGroup * > 
joint_state_group_map_
std::map< std::string,
JointState * > 
joint_state_map_
std::vector< JointState * > joint_state_vector_
const boost::shared_ptr< const
KinematicModel
kinematic_model_
std::map< std::string,
unsigned int > 
kinematic_state_index_map_
std::map< std::string,
LinkState * > 
link_state_map_
std::vector< LinkState * > link_state_vector_

Detailed Description

Definition of a kinematic state - the parts of the robot state which can change. It is not thread safe, however multiple instances can be created.

Definition at line 46 of file kinematic_state.h.


Constructor & Destructor Documentation

planning_models::KinematicState::KinematicState ( const boost::shared_ptr< const KinematicModel kinematic_model  ) 
Author:
E. Gil Jones, Ioan Sucan

Definition at line 39 of file kinematic_state.cpp.

planning_models::KinematicState::KinematicState ( const KinematicState state  ) 

Definition at line 80 of file kinematic_state.cpp.

planning_models::KinematicState::~KinematicState ( void   ) 

Definition at line 118 of file kinematic_state.cpp.


Member Function Documentation

bool planning_models::KinematicState::areJointsWithinBounds ( const std::vector< std::string > &  joints  )  const

Definition at line 255 of file kinematic_state.cpp.

planning_models::KinematicState::AttachedBodyState * planning_models::KinematicState::getAttachedBodyState ( const std::string &  attached  )  const

Get an attached body state by its name.

Definition at line 342 of file kinematic_state.cpp.

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

Definition at line 445 of file kinematic_state.h.

std::vector< planning_models::KinematicState::LinkState * > planning_models::KinematicState::getChildLinkStates ( const std::string &  link_name  )  const

Definition at line 215 of file kinematic_state.cpp.

unsigned int planning_models::KinematicState::getDimension (  )  const [inline]

Definition at line 394 of file kinematic_state.h.

planning_models::KinematicState::JointState * planning_models::KinematicState::getJointState ( const std::string &  joint  )  const

Get a joint state by its name.

Definition at line 330 of file kinematic_state.cpp.

planning_models::KinematicState::JointStateGroup * planning_models::KinematicState::getJointStateGroup ( const std::string &  name  ) 

Get a group by its name.

Definition at line 301 of file kinematic_state.cpp.

const planning_models::KinematicState::JointStateGroup * planning_models::KinematicState::getJointStateGroup ( const std::string &  name  )  const

Get a group by its name.

Definition at line 295 of file kinematic_state.cpp.

const std::map<std::string, JointStateGroup*>& planning_models::KinematicState::getJointStateGroupMap (  )  const [inline]

Definition at line 450 of file kinematic_state.h.

void planning_models::KinematicState::getJointStateGroupNames ( std::vector< std::string > &  names  )  const

Definition at line 312 of file kinematic_state.cpp.

std::vector<JointState*>& planning_models::KinematicState::getJointStateVector (  )  [inline]

Definition at line 435 of file kinematic_state.h.

const std::vector<JointState*>& planning_models::KinematicState::getJointStateVector (  )  const [inline]

Definition at line 430 of file kinematic_state.h.

const boost::shared_ptr<const KinematicModel> planning_models::KinematicState::getKinematicModel (  )  const [inline]

Definition at line 389 of file kinematic_state.h.

const std::map<std::string, unsigned int> planning_models::KinematicState::getKinematicStateIndexMap (  )  const [inline]

Definition at line 457 of file kinematic_state.h.

void planning_models::KinematicState::getKinematicStateValues ( std::map< std::string, double > &  joint_state_values  )  const

Definition at line 181 of file kinematic_state.cpp.

void planning_models::KinematicState::getKinematicStateValues ( std::vector< double > &  joint_state_values  )  const

Definition at line 166 of file kinematic_state.cpp.

planning_models::KinematicState::LinkState * planning_models::KinematicState::getLinkState ( const std::string &  link  )  const

Get a link state by its name.

Definition at line 336 of file kinematic_state.cpp.

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

Definition at line 440 of file kinematic_state.h.

bool planning_models::KinematicState::hasJointState ( const std::string &  joint  )  const

Check if a joint is part of this state.

Definition at line 321 of file kinematic_state.cpp.

bool planning_models::KinematicState::hasJointStateGroup ( const std::string &  name  )  const

Check if a group exists.

Definition at line 307 of file kinematic_state.cpp.

bool planning_models::KinematicState::hasLinkState ( const std::string &  joint  )  const

Check if a link is updated by this state.

Definition at line 325 of file kinematic_state.cpp.

bool planning_models::KinematicState::isJointWithinBounds ( const std::string &  joint  )  const

Definition at line 246 of file kinematic_state.cpp.

void planning_models::KinematicState::printStateInfo ( std::ostream &  out = std::cout  )  const

Print information about the constructed model.

Definition at line 670 of file kinematic_state.cpp.

void planning_models::KinematicState::printTransform ( const std::string &  st,
const btTransform &  t,
std::ostream &  out = std::cout 
) const

Definition at line 721 of file kinematic_state.cpp.

void planning_models::KinematicState::printTransforms ( std::ostream &  out = std::cout  )  const

Print the pose of every link.

Definition at line 730 of file kinematic_state.cpp.

bool planning_models::KinematicState::setKinematicState ( const std::map< std::string, double > &  joint_state_map  ) 

Definition at line 155 of file kinematic_state.cpp.

bool planning_models::KinematicState::setKinematicState ( const std::vector< double > &  joint_state_values  ) 

Definition at line 134 of file kinematic_state.cpp.

void planning_models::KinematicState::setKinematicStateToDefault ( void   ) 

Definition at line 225 of file kinematic_state.cpp.

void planning_models::KinematicState::setLinkStatesParents (  )  [private]

Definition at line 272 of file kinematic_state.cpp.

void planning_models::KinematicState::updateKinematicLinks (  ) 

Definition at line 196 of file kinematic_state.cpp.

bool planning_models::KinematicState::updateKinematicStateWithLinkAt ( const std::string &  link_name,
const btTransform &  transform 
)

Definition at line 203 of file kinematic_state.cpp.


Member Data Documentation

Definition at line 486 of file kinematic_state.h.

Definition at line 476 of file kinematic_state.h.

Definition at line 488 of file kinematic_state.h.

Definition at line 480 of file kinematic_state.h.

Definition at line 479 of file kinematic_state.h.

const boost::shared_ptr<const KinematicModel> planning_models::KinematicState::kinematic_model_ [private]

Definition at line 474 of file kinematic_state.h.

std::map<std::string, unsigned int> planning_models::KinematicState::kinematic_state_index_map_ [private]

Definition at line 477 of file kinematic_state.h.

Definition at line 483 of file kinematic_state.h.

Definition at line 482 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