moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Definition of a kinematic model. This class is not thread safe, however multiple instances can be created. More...
#include <robot_model.h>
Public Member Functions | |
RobotModel (const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model) | |
Construct a kinematic model from a parsed description and a list of planning groups. | |
~RobotModel () | |
Destructor. Clear all memory. | |
const std::string & | getName () const |
Get the model name. | |
const std::string & | getModelFrame () const |
Get the frame in which the transforms for this model are computed (when using a RobotState). This frame depends on the root joint. As such, the frame is either extracted from SRDF, or it is assumed to be the name of the root link. | |
bool | isEmpty () const |
Return true if the model is empty (has no root link, no joints) | |
const urdf::ModelInterfaceSharedPtr & | getURDF () const |
Get the parsed URDF model. | |
const srdf::ModelConstSharedPtr & | getSRDF () const |
Get the parsed SRDF model. | |
void | printModelInfo (std::ostream &out) const |
Print information about the constructed model. | |
void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, double *values) const |
Compute the random values for a RobotState. | |
void | getVariableDefaultPositions (double *values) const |
Compute the default values for a RobotState. | |
void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values) const |
Compute the random values for a RobotState. | |
void | getVariableDefaultPositions (std::vector< double > &values) const |
Compute the default values for a RobotState. | |
void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, std::map< std::string, double > &values) const |
Compute the random values for a RobotState. | |
void | getVariableDefaultPositions (std::map< std::string, double > &values) const |
Compute the default values for a RobotState. | |
bool | enforcePositionBounds (double *state) const |
bool | enforcePositionBounds (double *state, const JointBoundsVector &active_joint_bounds) const |
bool | satisfiesPositionBounds (const double *state, double margin=0.0) const |
bool | satisfiesPositionBounds (const double *state, const JointBoundsVector &active_joint_bounds, double margin=0.0) const |
double | getMaximumExtent () const |
double | getMaximumExtent (const JointBoundsVector &active_joint_bounds) const |
double | distance (const double *state1, const double *state2) const |
Return the sum of joint distances between two states. An L1 norm. Only considers active joints. | |
void | interpolate (const double *from, const double *to, double t, double *state) const |
std::size_t | getVariableCount () const |
Get the number of variables that describe this model. | |
const std::vector< std::string > & | getVariableNames () const |
Get the names of the variables that make up the joints that form this state. Fixed joints have no DOF, so they are not here, but the variables for mimic joints are included. The number of returned elements is always equal to getVariableCount() | |
const VariableBounds & | getVariableBounds (const std::string &variable) const |
Get the bounds for a specific variable. Throw an exception of variable is not found. | |
const JointBoundsVector & | getActiveJointModelsBounds () const |
Get the bounds for all the active joints. | |
void | getMissingVariableNames (const std::vector< std::string > &variables, std::vector< std::string > &missing_variables) const |
size_t | getVariableIndex (const std::string &variable) const |
Get the index of a variable in the robot state. | |
const JointModel * | getCommonRoot (const JointModel *a, const JointModel *b) const |
Get the deepest joint in the kinematic tree that is a common parent of both joints passed as argument. | |
void | setKinematicsAllocators (const std::map< std::string, SolverAllocatorFn > &allocators) |
A map of known kinematics solvers (associated to their group name) | |
Access to joint models | |
const JointModel * | getRootJoint () const |
Get the root joint. There will be one root joint unless the model is empty. This is either extracted from the SRDF, or a fixed joint is assumed, if no specification is given. | |
const std::string & | getRootJointName () const |
Return the name of the root joint. Throws an exception if there is no root joint. | |
bool | hasJointModel (const std::string &name) const |
Check if a joint exists. Return true if it does. | |
const JointModel * | getJointModel (const std::string &joint) const |
Get a joint by its name. Output error and return nullptr when the joint is missing. | |
const JointModel * | getJointModel (size_t index) const |
Get a joint by its index. Output error and return nullptr when the link is missing. | |
JointModel * | getJointModel (const std::string &joint) |
Get a joint by its name. Output error and return nullptr when the joint is missing. | |
const std::vector< const JointModel * > & | getJointModels () const |
Get the array of joints, in the order they appear in the robot state. | |
const std::vector< JointModel * > & | getJointModels () |
Get the array of joints, in the order they appear in the robot state. This includes all types of joints (including mimic & fixed), as opposed to JointModelGroup::getJointModels(). | |
const std::vector< std::string > & | getJointModelNames () const |
Get the array of joint names, in the order they appear in the robot state. | |
const std::vector< const JointModel * > & | getActiveJointModels () const |
Get the array of joints that are active (not fixed, not mimic) in this model. | |
const std::vector< std::string > & | getActiveJointModelNames () const |
Get the array of active joint names, in the order they appear in the robot state. | |
const std::vector< JointModel * > & | getActiveJointModels () |
Get the array of joints that are active (not fixed, not mimic) in this model. | |
const std::vector< const JointModel * > & | getSingleDOFJointModels () const |
This is a list of all single-dof joints (including mimic joints) | |
const std::vector< const JointModel * > & | getMultiDOFJointModels () const |
This is a list of all multi-dof joints. | |
const std::vector< const JointModel * > & | getContinuousJointModels () const |
Get the array of continuous joints, in the order they appear in the robot state. | |
const std::vector< const JointModel * > & | getMimicJointModels () const |
Get the array of mimic joints, in the order they appear in the robot state. | |
const JointModel * | getJointOfVariable (int variable_index) const |
const JointModel * | getJointOfVariable (const std::string &variable) const |
std::size_t | getJointModelCount () const |
Access to joint groups | |
bool | hasJointModelGroup (const std::string &group) const |
Check if the JointModelGroup group exists. | |
const JointModelGroup * | getJointModelGroup (const std::string &name) const |
Get a joint group from this model (by name) | |
JointModelGroup * | getJointModelGroup (const std::string &name) |
Get a joint group from this model (by name) | |
const std::vector< const JointModelGroup * > & | getJointModelGroups () const |
Get the available joint groups. | |
const std::vector< JointModelGroup * > & | getJointModelGroups () |
Get the available joint groups. | |
const std::vector< std::string > & | getJointModelGroupNames () const |
Get the names of all groups that are defined for this model. | |
bool | hasEndEffector (const std::string &eef) const |
Check if an end effector exists. | |
const JointModelGroup * | getEndEffector (const std::string &name) const |
Get the joint group that corresponds to a given end-effector name. | |
JointModelGroup * | getEndEffector (const std::string &name) |
Get the joint group that corresponds to a given end-effector name. | |
const std::vector< const JointModelGroup * > & | getEndEffectors () const |
Get the map between end effector names and the groups they correspond to. | |
Protected Member Functions | |
void | computeFixedTransforms (const LinkModel *link, const Eigen::Isometry3d &transform, LinkTransformMap &associated_transforms) |
Get the transforms between link and all its rigidly attached descendants. | |
const JointModel * | computeCommonRoot (const JointModel *a, const JointModel *b) const |
Given two joints, find their common root. | |
void | updateMimicJoints (double *values) const |
Update the variable values for the state of a group with respect to the mimic joints. | |
Protected Attributes | |
std::string | model_name_ |
The name of the robot. | |
std::string | model_frame_ |
The reference (base) frame for this model. The frame is either extracted from the SRDF as a virtual joint, or it is assumed to be the name of the root link in the URDF. | |
srdf::ModelConstSharedPtr | srdf_ |
urdf::ModelInterfaceSharedPtr | urdf_ |
const LinkModel * | root_link_ |
The first physical link for the robot. | |
LinkModelMap | link_model_map_ |
A map from link names to their instances. | |
std::vector< LinkModel * > | link_model_vector_ |
The vector of links that are updated when computeTransforms() is called, in the order they are updated. | |
std::vector< const LinkModel * > | link_model_vector_const_ |
The vector of links that are updated when computeTransforms() is called, in the order they are updated. | |
std::vector< std::string > | link_model_names_vector_ |
The vector of link names that corresponds to link_model_vector_. | |
std::vector< const LinkModel * > | link_models_with_collision_geometry_vector_ |
Only links that have collision geometry specified. | |
std::vector< std::string > | link_model_names_with_collision_geometry_vector_ |
The vector of link names that corresponds to link_models_with_collision_geometry_vector_. | |
std::size_t | link_geometry_count_ |
Total number of geometric shapes in this model. | |
const JointModel * | root_joint_ |
The root joint. | |
JointModelMap | joint_model_map_ |
A map from joint names to their instances. | |
std::vector< JointModel * > | joint_model_vector_ |
The vector of joints in the model, in the order they appear in the state vector. | |
std::vector< const JointModel * > | joint_model_vector_const_ |
The vector of joints in the model, in the order they appear in the state vector. | |
std::vector< std::string > | joint_model_names_vector_ |
The vector of joint names that corresponds to joint_model_vector_. | |
std::vector< JointModel * > | active_joint_model_vector_ |
The vector of joints in the model, in the order they appear in the state vector. | |
std::vector< std::string > | active_joint_model_names_vector_ |
The vector of joint names that corresponds to active_joint_model_vector_. | |
std::vector< const JointModel * > | active_joint_model_vector_const_ |
The vector of joints in the model, in the order they appear in the state vector. | |
std::vector< const JointModel * > | continuous_joint_model_vector_ |
The set of continuous joints this model contains. | |
std::vector< const JointModel * > | mimic_joints_ |
The set of mimic joints this model contains. | |
std::vector< const JointModel * > | single_dof_joints_ |
std::vector< const JointModel * > | multi_dof_joints_ |
std::vector< int > | common_joint_roots_ |
For every two joints, the index of the common root for the joints is stored. | |
std::vector< std::string > | variable_names_ |
The names of the DOF that make up this state (this is just a sequence of joint variable names; not necessarily joint names!) | |
std::size_t | variable_count_ |
Get the number of variables necessary to describe this model. | |
VariableIndexMap | joint_variables_index_map_ |
The state includes all the joint variables that make up the joints the state consists of. This map gives the position in the state vector of the group for each of these variables. Additionally, it includes the names of the joints and the index for the first variable of that joint. | |
std::vector< int > | active_joint_model_start_index_ |
JointBoundsVector | active_joint_models_bounds_ |
The bounds for all the active joint models. | |
std::vector< const JointModel * > | joints_of_variable_ |
The joints that correspond to each variable index. | |
JointModelGroupMap | joint_model_group_map_ |
A map from group names to joint groups. | |
JointModelGroupMap | end_effectors_map_ |
The known end effectors. | |
std::vector< JointModelGroup * > | joint_model_groups_ |
The array of joint model groups, in alphabetical order. | |
std::vector< const JointModelGroup * > | joint_model_groups_const_ |
The array of joint model groups, in alphabetical order. | |
std::vector< std::string > | joint_model_group_names_ |
A vector of all group names, in alphabetical order. | |
std::vector< const JointModelGroup * > | end_effectors_ |
The array of end-effectors, in alphabetical order. | |
Access to link models | |
const LinkModel * | getRootLink () const |
Get the physical root link of the robot. | |
const std::string & | getRootLinkName () const |
Get the name of the root link of the robot. | |
bool | hasLinkModel (const std::string &name) const |
Check if a link exists. Return true if it does. | |
const LinkModel * | getLinkModel (const std::string &link, bool *has_link=nullptr) const |
Get a link by its name. Output error and return nullptr when the link is missing. | |
const LinkModel * | getLinkModel (size_t index) const |
Get a link by its index. Output error and return nullptr when the link is missing. | |
LinkModel * | getLinkModel (const std::string &link, bool *has_link=nullptr) |
Get a link by its name. Output error and return nullptr when the link is missing. | |
const std::vector< const LinkModel * > & | getLinkModels () const |
Get the array of links | |
const std::vector< LinkModel * > & | getLinkModels () |
Get the array of links | |
const std::vector< std::string > & | getLinkModelNames () const |
Get the link names (of all links) | |
const std::vector< const LinkModel * > & | getLinkModelsWithCollisionGeometry () const |
Get the link models that have some collision geometry associated to themselves. | |
const std::vector< std::string > & | getLinkModelNamesWithCollisionGeometry () const |
Get the names of the link models that have some collision geometry associated to themselves. | |
std::size_t | getLinkModelCount () const |
std::size_t | getLinkGeometryCount () const |
static const moveit::core::LinkModel * | getRigidlyConnectedParentLinkModel (const LinkModel *link) |
Get the latest link upwards the kinematic tree, which is only connected via fixed joints. | |
Definition of a kinematic model. This class is not thread safe, however multiple instances can be created.
Definition at line 75 of file robot_model.h.
moveit::core::RobotModel::RobotModel | ( | const urdf::ModelInterfaceSharedPtr & | urdf_model, |
const srdf::ModelConstSharedPtr & | srdf_model | ||
) |
Construct a kinematic model from a parsed description and a list of planning groups.
Definition at line 61 of file robot_model.cpp.
moveit::core::RobotModel::~RobotModel | ( | ) |
Destructor. Clear all memory.
Definition at line 69 of file robot_model.cpp.
|
protected |
Given two joints, find their common root.
|
protected |
Get the transforms between link and all its rigidly attached descendants.
Definition at line 1637 of file robot_model.cpp.
double moveit::core::RobotModel::distance | ( | const double * | state1, |
const double * | state2 | ||
) | const |
Return the sum of joint distances between two states. An L1 norm. Only considers active joints.
Definition at line 1488 of file robot_model.cpp.
|
inline |
Definition at line 339 of file robot_model.h.
bool moveit::core::RobotModel::enforcePositionBounds | ( | double * | state, |
const JointBoundsVector & | active_joint_bounds | ||
) | const |
|
inline |
Get the array of active joint names, in the order they appear in the robot state.
Definition at line 176 of file robot_model.h.
|
inline |
Get the array of joints that are active (not fixed, not mimic) in this model.
Definition at line 182 of file robot_model.h.
|
inline |
Get the array of joints that are active (not fixed, not mimic) in this model.
Definition at line 170 of file robot_model.h.
|
inline |
Get the bounds for all the active joints.
Definition at line 439 of file robot_model.h.
|
inline |
Get the deepest joint in the kinematic tree that is a common parent of both joints passed as argument.
Definition at line 451 of file robot_model.h.
|
inline |
Get the array of continuous joints, in the order they appear in the robot state.
Definition at line 201 of file robot_model.h.
JointModelGroup * moveit::core::RobotModel::getEndEffector | ( | const std::string & | name | ) |
Get the joint group that corresponds to a given end-effector name.
Definition at line 493 of file robot_model.cpp.
const JointModelGroup * moveit::core::RobotModel::getEndEffector | ( | const std::string & | name | ) | const |
Get the joint group that corresponds to a given end-effector name.
Definition at line 479 of file robot_model.cpp.
|
inline |
Get the map between end effector names and the groups they correspond to.
Definition at line 410 of file robot_model.h.
JointModel * moveit::core::RobotModel::getJointModel | ( | const std::string & | joint | ) |
Get a joint by its name. Output error and return nullptr when the joint is missing.
Definition at line 1323 of file robot_model.cpp.
const JointModel * moveit::core::RobotModel::getJointModel | ( | const std::string & | joint | ) | const |
Get a joint by its name. Output error and return nullptr when the joint is missing.
Definition at line 1303 of file robot_model.cpp.
const JointModel * moveit::core::RobotModel::getJointModel | ( | size_t | index | ) | const |
Get a joint by its index. Output error and return nullptr when the link is missing.
Definition at line 1312 of file robot_model.cpp.
|
inline |
Definition at line 223 of file robot_model.h.
JointModelGroup * moveit::core::RobotModel::getJointModelGroup | ( | const std::string & | name | ) |
Get a joint group from this model (by name)
Definition at line 523 of file robot_model.cpp.
const JointModelGroup * moveit::core::RobotModel::getJointModelGroup | ( | const std::string & | name | ) | const |
Get a joint group from this model (by name)
Definition at line 512 of file robot_model.cpp.
|
inline |
Get the names of all groups that are defined for this model.
Definition at line 395 of file robot_model.h.
|
inline |
Get the available joint groups.
Definition at line 389 of file robot_model.h.
|
inline |
Get the available joint groups.
Definition at line 383 of file robot_model.h.
|
inline |
Get the array of joint names, in the order they appear in the robot state.
Definition at line 164 of file robot_model.h.
|
inline |
Get the array of joints, in the order they appear in the robot state. This includes all types of joints (including mimic & fixed), as opposed to JointModelGroup::getJointModels().
Definition at line 158 of file robot_model.h.
|
inline |
Get the array of joints, in the order they appear in the robot state.
Definition at line 150 of file robot_model.h.
|
inline |
|
inline |
|
inline |
Definition at line 305 of file robot_model.h.
LinkModel * moveit::core::RobotModel::getLinkModel | ( | const std::string & | link, |
bool * | has_link = nullptr |
||
) |
Get a link by its name. Output error and return nullptr when the link is missing.
Definition at line 1348 of file robot_model.cpp.
const LinkModel * moveit::core::RobotModel::getLinkModel | ( | const std::string & | link, |
bool * | has_link = nullptr |
||
) | const |
Get a link by its name. Output error and return nullptr when the link is missing.
Definition at line 1332 of file robot_model.cpp.
const LinkModel * moveit::core::RobotModel::getLinkModel | ( | size_t | index | ) | const |
Get a link by its index. Output error and return nullptr when the link is missing.
Definition at line 1337 of file robot_model.cpp.
|
inline |
Definition at line 300 of file robot_model.h.
|
inline |
Get the link names (of all links)
Definition at line 283 of file robot_model.h.
|
inline |
Get the names of the link models that have some collision geometry associated to themselves.
Definition at line 295 of file robot_model.h.
|
inline |
Get the array of links
Definition at line 277 of file robot_model.h.
|
inline |
Get the array of links
Definition at line 271 of file robot_model.h.
|
inline |
Get the link models that have some collision geometry associated to themselves.
Definition at line 289 of file robot_model.h.
|
inline |
Definition at line 350 of file robot_model.h.
double moveit::core::RobotModel::getMaximumExtent | ( | const JointBoundsVector & | active_joint_bounds | ) | const |
Definition at line 1449 of file robot_model.cpp.
|
inline |
Get the array of mimic joints, in the order they appear in the robot state.
Definition at line 208 of file robot_model.h.
void moveit::core::RobotModel::getMissingVariableNames | ( | const std::vector< std::string > & | variables, |
std::vector< std::string > & | missing_variables | ||
) | const |
|
inline |
Get the frame in which the transforms for this model are computed (when using a RobotState). This frame depends on the root joint. As such, the frame is either extracted from SRDF, or it is assumed to be the name of the root link.
Definition at line 94 of file robot_model.h.
|
inline |
This is a list of all multi-dof joints.
Definition at line 194 of file robot_model.h.
|
inline |
Get the model name.
Definition at line 85 of file robot_model.h.
|
static |
Get the latest link upwards the kinematic tree, which is only connected via fixed joints.
This is useful, if the link should be warped to a specific pose using updateStateWithLinkAt(). As updateStateWithLinkAt() warps only the specified link and its descendants, you might not achieve what you expect, if link is an abstract frame name. Considering the following example: root -> arm0 -> ... -> armN -> wrist – grasp_frame – palm -> end effector ... Calling updateStateWithLinkAt(grasp_frame), will not warp the end effector, which is probably what you went for. Instead, updateStateWithLinkAt(getRigidlyConnectedParentLinkModel(grasp_frame), ...) will actually warp wrist (and all its descendants).
Definition at line 1367 of file robot_model.cpp.
const JointModel * moveit::core::RobotModel::getRootJoint | ( | ) | const |
Get the root joint. There will be one root joint unless the model is empty. This is either extracted from the SRDF, or a fixed joint is assumed, if no specification is given.
Definition at line 79 of file robot_model.cpp.
|
inline |
Return the name of the root joint. Throws an exception if there is no root joint.
Definition at line 131 of file robot_model.h.
const LinkModel * moveit::core::RobotModel::getRootLink | ( | ) | const |
Get the physical root link of the robot.
Definition at line 84 of file robot_model.cpp.
|
inline |
Get the name of the root link of the robot.
Definition at line 238 of file robot_model.h.
|
inline |
This is a list of all single-dof joints (including mimic joints)
Definition at line 188 of file robot_model.h.
|
inline |
Get the parsed SRDF model.
Definition at line 112 of file robot_model.h.
|
inline |
Get the parsed URDF model.
Definition at line 106 of file robot_model.h.
|
inline |
Get the bounds for a specific variable. Throw an exception of variable is not found.
Definition at line 433 of file robot_model.h.
|
inline |
Get the number of variables that describe this model.
Definition at line 418 of file robot_model.h.
void moveit::core::RobotModel::getVariableDefaultPositions | ( | double * | values | ) | const |
Compute the default values for a RobotState.
Definition at line 1410 of file robot_model.cpp.
void moveit::core::RobotModel::getVariableDefaultPositions | ( | std::map< std::string, double > & | values | ) | const |
Compute the default values for a RobotState.
Definition at line 1417 of file robot_model.cpp.
|
inline |
Compute the default values for a RobotState.
Definition at line 326 of file robot_model.h.
size_t moveit::core::RobotModel::getVariableIndex | ( | const std::string & | variable | ) | const |
Get the index of a variable in the robot state.
Definition at line 1441 of file robot_model.cpp.
|
inline |
Get the names of the variables that make up the joints that form this state. Fixed joints have no DOF, so they are not here, but the variables for mimic joints are included. The number of returned elements is always equal to getVariableCount()
Definition at line 427 of file robot_model.h.
void moveit::core::RobotModel::getVariableRandomPositions | ( | random_numbers::RandomNumberGenerator & | rng, |
double * | values | ||
) | const |
Compute the random values for a RobotState.
Definition at line 1393 of file robot_model.cpp.
void moveit::core::RobotModel::getVariableRandomPositions | ( | random_numbers::RandomNumberGenerator & | rng, |
std::map< std::string, double > & | values | ||
) | const |
Compute the random values for a RobotState.
Definition at line 1400 of file robot_model.cpp.
|
inline |
Compute the random values for a RobotState.
Definition at line 319 of file robot_model.h.
bool moveit::core::RobotModel::hasEndEffector | ( | const std::string & | eef | ) | const |
Check if an end effector exists.
Definition at line 474 of file robot_model.cpp.
bool moveit::core::RobotModel::hasJointModel | ( | const std::string & | name | ) | const |
Check if a joint exists. Return true if it does.
Definition at line 1293 of file robot_model.cpp.
bool moveit::core::RobotModel::hasJointModelGroup | ( | const std::string & | group | ) | const |
Check if the JointModelGroup group exists.
Definition at line 507 of file robot_model.cpp.
bool moveit::core::RobotModel::hasLinkModel | ( | const std::string & | name | ) | const |
Check if a link exists. Return true if it does.
If this is followed by a call to getLinkModel(), better use the latter with the has_link argument
Definition at line 1298 of file robot_model.cpp.
void moveit::core::RobotModel::interpolate | ( | const double * | from, |
const double * | to, | ||
double | t, | ||
double * | state | ||
) | const |
Interpolate between "from" state, to "to" state. Mimic joints are correctly updated.
from | interpolate from this state |
to | to this state |
t | a fraction in the range [0 1]. If 1, the result matches "to" state exactly. |
state | holds the result |
Definition at line 1500 of file robot_model.cpp.
|
inline |
Return true if the model is empty (has no root link, no joints)
Definition at line 100 of file robot_model.h.
void moveit::core::RobotModel::printModelInfo | ( | std::ostream & | out | ) | const |
Print information about the constructed model.
Definition at line 1586 of file robot_model.cpp.
bool moveit::core::RobotModel::satisfiesPositionBounds | ( | const double * | state, |
const JointBoundsVector & | active_joint_bounds, | ||
double | margin = 0.0 |
||
) | const |
|
inline |
Definition at line 344 of file robot_model.h.
void moveit::core::RobotModel::setKinematicsAllocators | ( | const std::map< std::string, SolverAllocatorFn > & | allocators | ) |
A map of known kinematics solvers (associated to their group name)
Definition at line 1514 of file robot_model.cpp.
|
protected |
Update the variable values for the state of a group with respect to the mimic joints.
Definition at line 1383 of file robot_model.cpp.
|
protected |
The vector of joint names that corresponds to active_joint_model_vector_.
Definition at line 534 of file robot_model.h.
|
protected |
Definition at line 572 of file robot_model.h.
|
protected |
The vector of joints in the model, in the order they appear in the state vector.
Definition at line 531 of file robot_model.h.
|
protected |
The vector of joints in the model, in the order they appear in the state vector.
Definition at line 537 of file robot_model.h.
|
protected |
The bounds for all the active joint models.
Definition at line 575 of file robot_model.h.
|
protected |
For every two joints, the index of the common root for the joints is stored.
for jointA, jointB the index of the common root is located in the array at location jointA->getJointIndex() * nr.joints + jointB->getJointIndex(). The size of this array is nr.joints * nr.joints
Definition at line 556 of file robot_model.h.
|
protected |
The set of continuous joints this model contains.
Definition at line 540 of file robot_model.h.
|
protected |
The array of end-effectors, in alphabetical order.
Definition at line 598 of file robot_model.h.
|
protected |
The known end effectors.
Definition at line 586 of file robot_model.h.
|
protected |
A map from group names to joint groups.
Definition at line 583 of file robot_model.h.
|
protected |
A vector of all group names, in alphabetical order.
Definition at line 595 of file robot_model.h.
|
protected |
The array of joint model groups, in alphabetical order.
Definition at line 589 of file robot_model.h.
|
protected |
The array of joint model groups, in alphabetical order.
Definition at line 592 of file robot_model.h.
|
protected |
A map from joint names to their instances.
Definition at line 519 of file robot_model.h.
|
protected |
The vector of joint names that corresponds to joint_model_vector_.
Definition at line 528 of file robot_model.h.
|
protected |
The vector of joints in the model, in the order they appear in the state vector.
Definition at line 522 of file robot_model.h.
|
protected |
The vector of joints in the model, in the order they appear in the state vector.
Definition at line 525 of file robot_model.h.
|
protected |
The state includes all the joint variables that make up the joints the state consists of. This map gives the position in the state vector of the group for each of these variables. Additionally, it includes the names of the joints and the index for the first variable of that joint.
Definition at line 570 of file robot_model.h.
|
protected |
The joints that correspond to each variable index.
Definition at line 578 of file robot_model.h.
|
protected |
Total number of geometric shapes in this model.
Definition at line 511 of file robot_model.h.
|
protected |
A map from link names to their instances.
Definition at line 493 of file robot_model.h.
|
protected |
The vector of link names that corresponds to link_model_vector_.
Definition at line 502 of file robot_model.h.
|
protected |
The vector of link names that corresponds to link_models_with_collision_geometry_vector_.
Definition at line 508 of file robot_model.h.
|
protected |
The vector of links that are updated when computeTransforms() is called, in the order they are updated.
Definition at line 496 of file robot_model.h.
|
protected |
The vector of links that are updated when computeTransforms() is called, in the order they are updated.
Definition at line 499 of file robot_model.h.
|
protected |
Only links that have collision geometry specified.
Definition at line 505 of file robot_model.h.
|
protected |
The set of mimic joints this model contains.
Definition at line 543 of file robot_model.h.
|
protected |
The reference (base) frame for this model. The frame is either extracted from the SRDF as a virtual joint, or it is assumed to be the name of the root link in the URDF.
Definition at line 481 of file robot_model.h.
|
protected |
The name of the robot.
Definition at line 477 of file robot_model.h.
|
protected |
Definition at line 547 of file robot_model.h.
|
protected |
The root joint.
Definition at line 516 of file robot_model.h.
|
protected |
The first physical link for the robot.
Definition at line 490 of file robot_model.h.
|
protected |
Definition at line 545 of file robot_model.h.
|
protected |
Definition at line 483 of file robot_model.h.
|
protected |
Definition at line 485 of file robot_model.h.
|
protected |
Get the number of variables necessary to describe this model.
Definition at line 565 of file robot_model.h.
|
protected |
The names of the DOF that make up this state (this is just a sequence of joint variable names; not necessarily joint names!)
Definition at line 562 of file robot_model.h.