$search
#include <kinematic_state.h>
Public Member Functions | |
unsigned int | getDimension () const |
const KinematicModel::JointModelGroup * | getJointModelGroup () |
const std::vector< std::string > & | getJointNames () const |
const std::vector< JointState * > & | getJointRoots () const |
JointState * | getJointState (const std::string &joint) const |
Get a joint state by its name. | |
const std::vector< JointState * > & | getJointStateVector () 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 |
const std::string & | getName () const |
bool | hasJointState (const std::string &joint) const |
Check if a joint is part of this group. | |
JointStateGroup (const KinematicModel::JointModelGroup *jmg, const KinematicState *owner) | |
bool | setKinematicState (const std::map< std::string, double > &joint_state_map) |
Perform forward kinematics starting at the roots within a group. Links that are not in the group are also updated, but transforms for joints that are not in the group are not recomputed. | |
bool | setKinematicState (const std::vector< double > &joint_state_values) |
Perform forward kinematics starting at the roots within a group. Links that are not in the group are also updated, but transforms for joints that are not in the group are not recomputed. | |
void | setKinematicStateToDefault () |
Bring the group to a default state. All joints are at 0. If 0 is not within the bounds of the joint, the middle of the bounds is used. | |
void | updateKinematicLinks () |
bool | updatesLinkState (const std::string &joint) const |
Check if a link is updated by this group. | |
~JointStateGroup (void) | |
Private Attributes | |
unsigned int | dimension_ |
const KinematicModel::JointModelGroup * | joint_model_group_ |
std::vector< std::string > | joint_names_ |
Names of joints in the order they appear in the group state. | |
std::vector< JointState * > | joint_roots_ |
The list of joints that are roots in this group. | |
std::map< std::string, JointState * > | joint_state_map_ |
A map from joint names to their instances. | |
std::vector< JointState * > | joint_state_vector_ |
Joint instances in the order they appear in the group state. | |
boost::shared_ptr< KinematicModel > | kinematic_model_ |
The kinematic model that owns the group. | |
std::map< std::string, unsigned int > | kinematic_state_index_map_ |
std::vector< LinkState * > | updated_links_ |
The list of links that are updated when computeTransforms() is called, in the order they are updated. |
Definition at line 273 of file kinematic_state.h.
planning_models::KinematicState::JointStateGroup::JointStateGroup | ( | const KinematicModel::JointModelGroup * | jmg, | |
const KinematicState * | owner | |||
) |
Definition at line 572 of file kinematic_state.cpp.
planning_models::KinematicState::JointStateGroup::~JointStateGroup | ( | void | ) | [inline] |
Definition at line 281 of file kinematic_state.h.
unsigned int planning_models::KinematicState::JointStateGroup::getDimension | ( | ) | const [inline] |
Definition at line 294 of file kinematic_state.h.
const KinematicModel::JointModelGroup* planning_models::KinematicState::JointStateGroup::getJointModelGroup | ( | ) | [inline] |
Definition at line 285 of file kinematic_state.h.
const std::vector<std::string>& planning_models::KinematicState::JointStateGroup::getJointNames | ( | ) | const [inline] |
Definition at line 342 of file kinematic_state.h.
const std::vector<JointState*>& planning_models::KinematicState::JointStateGroup::getJointRoots | ( | ) | const [inline] |
Definition at line 332 of file kinematic_state.h.
planning_models::KinematicState::JointState * planning_models::KinematicState::JointStateGroup::getJointState | ( | const std::string & | joint | ) | const |
Get a joint state by its name.
Definition at line 704 of file kinematic_state.cpp.
const std::vector<JointState*>& planning_models::KinematicState::JointStateGroup::getJointStateVector | ( | ) | const [inline] |
Definition at line 347 of file kinematic_state.h.
const std::map<std::string, unsigned int>& planning_models::KinematicState::JointStateGroup::getKinematicStateIndexMap | ( | ) | const [inline] |
Definition at line 337 of file kinematic_state.h.
void planning_models::KinematicState::JointStateGroup::getKinematicStateValues | ( | std::map< std::string, double > & | joint_state_values | ) | const |
Definition at line 689 of file kinematic_state.cpp.
void planning_models::KinematicState::JointStateGroup::getKinematicStateValues | ( | std::vector< double > & | joint_state_values | ) | const |
Definition at line 674 of file kinematic_state.cpp.
const std::string& planning_models::KinematicState::JointStateGroup::getName | ( | void | ) | const [inline] |
Definition at line 289 of file kinematic_state.h.
bool planning_models::KinematicState::JointStateGroup::hasJointState | ( | const std::string & | joint | ) | const |
Check if a joint is part of this group.
Definition at line 611 of file kinematic_state.cpp.
bool planning_models::KinematicState::JointStateGroup::setKinematicState | ( | const std::map< std::string, double > & | joint_state_map | ) |
Perform forward kinematics starting at the roots within a group. Links that are not in the group are also updated, but transforms for joints that are not in the group are not recomputed.
Definition at line 644 of file kinematic_state.cpp.
bool planning_models::KinematicState::JointStateGroup::setKinematicState | ( | const std::vector< double > & | joint_state_values | ) |
Perform forward kinematics starting at the roots within a group. Links that are not in the group are also updated, but transforms for joints that are not in the group are not recomputed.
Definition at line 623 of file kinematic_state.cpp.
void planning_models::KinematicState::JointStateGroup::setKinematicStateToDefault | ( | void | ) |
Bring the group to a default state. All joints are at 0. If 0 is not within the bounds of the joint, the middle of the bounds is used.
Definition at line 662 of file kinematic_state.cpp.
void planning_models::KinematicState::JointStateGroup::updateKinematicLinks | ( | ) |
compute transforms using current joint values
Definition at line 655 of file kinematic_state.cpp.
bool planning_models::KinematicState::JointStateGroup::updatesLinkState | ( | const std::string & | joint | ) | const |
Check if a link is updated by this group.
Definition at line 615 of file kinematic_state.cpp.
unsigned int planning_models::KinematicState::JointStateGroup::dimension_ [private] |
Definition at line 359 of file kinematic_state.h.
const KinematicModel::JointModelGroup* planning_models::KinematicState::JointStateGroup::joint_model_group_ [private] |
Definition at line 357 of file kinematic_state.h.
std::vector<std::string> planning_models::KinematicState::JointStateGroup::joint_names_ [private] |
Names of joints in the order they appear in the group state.
Definition at line 363 of file kinematic_state.h.
std::vector<JointState*> planning_models::KinematicState::JointStateGroup::joint_roots_ [private] |
The list of joints that are roots in this group.
Definition at line 372 of file kinematic_state.h.
std::map<std::string, JointState*> planning_models::KinematicState::JointStateGroup::joint_state_map_ [private] |
A map from joint names to their instances.
Definition at line 369 of file kinematic_state.h.
std::vector<JointState*> planning_models::KinematicState::JointStateGroup::joint_state_vector_ [private] |
Joint instances in the order they appear in the group state.
Definition at line 366 of file kinematic_state.h.
boost::shared_ptr<KinematicModel> planning_models::KinematicState::JointStateGroup::kinematic_model_ [private] |
The kinematic model that owns the group.
Definition at line 355 of file kinematic_state.h.
std::map<std::string, unsigned int> planning_models::KinematicState::JointStateGroup::kinematic_state_index_map_ [private] |
Definition at line 360 of file kinematic_state.h.
std::vector<LinkState*> planning_models::KinematicState::JointStateGroup::updated_links_ [private] |
The list of links that are updated when computeTransforms() is called, in the order they are updated.
Definition at line 375 of file kinematic_state.h.