Classes | Public Member Functions | Private Member Functions | Private Attributes
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.
const JointStateGroupgetJointStateGroup (const std::string &name) const
 Get a group by its name.
JointStateGroupgetJointStateGroup (const std::string &name)
 Get a group by its name.
const std::map< std::string,
JointStateGroup * > & 
getJointStateGroupMap () const
void getJointStateGroupNames (std::vector< std::string > &names) const
const std::vector< JointState * > & getJointStateVector () const
std::vector< JointState * > & getJointStateVector ()
const KinematicModelgetKinematicModel () const
const std::map< std::string,
unsigned int > 
getKinematicStateIndexMap () const
void getKinematicStateValues (std::vector< double > &joint_state_values) const
void getKinematicStateValues (std::map< std::string, double > &joint_state_values) const
LinkStategetLinkState (const std::string &link) const
 Get a link state by its name.
const std::vector< LinkState * > & getLinkStateVector () const
const tf::TransformgetRootTransform () 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 KinematicModel *kinematic_model)
 KinematicState (const KinematicState &state)
void printStateInfo (std::ostream &out=std::cout) const
 Print information about the constructed model.
void printTransform (const std::string &st, const tf::Transform &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::vector< double > &joint_state_values)
bool setKinematicState (const std::map< std::string, double > &joint_state_map)
bool setKinematicState (const std::map< std::string, double > &joint_state_map, std::vector< std::string > &missing_links)
void setKinematicStateToDefault ()
void updateKinematicLinks ()
bool updateKinematicStateWithLinkAt (const std::string &link_name, const tf::Transform &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 KinematicModelkinematic_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 49 of file kinematic_state.h.


Constructor & Destructor Documentation

Author:
E. Gil Jones, Ioan Sucan

Definition at line 40 of file kinematic_state.cpp.

Definition at line 81 of file kinematic_state.cpp.

Definition at line 125 of file kinematic_state.cpp.


Member Function Documentation

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

Definition at line 274 of file kinematic_state.cpp.

Get an attached body state by its name.

Definition at line 361 of file kinematic_state.cpp.

Definition at line 464 of file kinematic_state.h.

Definition at line 243 of file kinematic_state.cpp.

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

Definition at line 413 of file kinematic_state.h.

Get a joint state by its name.

Definition at line 349 of file kinematic_state.cpp.

Get a group by its name.

Definition at line 314 of file kinematic_state.cpp.

Get a group by its name.

Definition at line 320 of file kinematic_state.cpp.

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

Definition at line 469 of file kinematic_state.h.

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

Definition at line 331 of file kinematic_state.cpp.

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

Definition at line 449 of file kinematic_state.h.

Definition at line 454 of file kinematic_state.h.

Definition at line 408 of file kinematic_state.h.

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

Definition at line 476 of file kinematic_state.h.

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

Definition at line 188 of file kinematic_state.cpp.

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

Definition at line 203 of file kinematic_state.cpp.

Get a link state by its name.

Definition at line 355 of file kinematic_state.cpp.

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

Definition at line 459 of file kinematic_state.h.

Definition at line 238 of file kinematic_state.cpp.

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

Check if a joint is part of this state.

Definition at line 340 of file kinematic_state.cpp.

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

Check if a group exists.

Definition at line 326 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 344 of file kinematic_state.cpp.

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

Definition at line 265 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 713 of file kinematic_state.cpp.

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

Definition at line 764 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 773 of file kinematic_state.cpp.

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

Definition at line 141 of file kinematic_state.cpp.

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

Definition at line 162 of file kinematic_state.cpp.

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

Definition at line 173 of file kinematic_state.cpp.

Definition at line 253 of file kinematic_state.cpp.

Definition at line 291 of file kinematic_state.cpp.

Definition at line 218 of file kinematic_state.cpp.

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

Definition at line 225 of file kinematic_state.cpp.


Member Data Documentation

Definition at line 507 of file kinematic_state.h.

Definition at line 497 of file kinematic_state.h.

Definition at line 509 of file kinematic_state.h.

Definition at line 501 of file kinematic_state.h.

Definition at line 500 of file kinematic_state.h.

Definition at line 495 of file kinematic_state.h.

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

Definition at line 498 of file kinematic_state.h.

Definition at line 504 of file kinematic_state.h.

Definition at line 503 of file kinematic_state.h.


The documentation for this class was generated from the following files:


planning_models
Author(s): Ioan Sucan/isucan@willowgarage.com
autogenerated on Mon Dec 2 2013 12:33:38