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 | |
const std::map< std::string, std::pair< double, double > > & | getAllVariableBounds () const |
Get bounds for all the variables in this model. Bounds are returned as a std::pair<lower,upper> | |
std::vector< std::string > | getChildJointModelNames (const LinkModel *parent) const |
Get the set of joint names that follow a parent link in the kinematic chain. | |
std::vector< std::string > | getChildJointModelNames (const JointModel *parent) const |
Get the set of joint names that follow a parent joint in the kinematic chain. | |
void | getChildJointModels (const LinkModel *parent, std::vector< const JointModel * > &links) const |
Get the set of joint models that follow a parent link in the kinematic chain. | |
void | getChildJointModels (const JointModel *parent, std::vector< const JointModel * > &links) const |
Get the set of joint models that follow a parent joint in the kinematic chain. | |
std::vector< std::string > | getChildLinkModelNames (const LinkModel *parent) const |
Get the set of link names that follow a parent link in the kinematic chain. | |
std::vector< std::string > | getChildLinkModelNames (const JointModel *parent) const |
Get the set of link names that follow a parent link in the kinematic chain. | |
void | getChildLinkModels (const LinkModel *parent, std::vector< const LinkModel * > &links) const |
Get the set of link models that follow a parent link in the kinematic chain. | |
void | getChildLinkModels (const JointModel *parent, std::vector< const LinkModel * > &links) const |
Get the set of link models that follow a parent joint in the kinematic chain. | |
const std::vector< const JointModel * > & | getContinuousJointModels () const |
Get the array of continuous joints, in the order they appear in the robot state. | |
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::map< std::string, JointModelGroup * > & | getEndEffectorsMap () const |
Get the map between end effector names and the groups they correspond to. | |
const JointModel * | getJointModel (const std::string &joint) const |
Get a joint by its name. | |
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::map< std::string, srdf::Model::Group > & | getJointModelGroupConfigMap () const |
Get the map between joint group names and the SRDF group object. | |
const std::map< std::string, JointModelGroup * > & | getJointModelGroupMap () const |
Get the map between joint group names and the groups. | |
const std::vector< std::string > & | getJointModelGroupNames () const |
Get the names of all groups that are defined for this model. | |
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 * > & | 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. | |
const std::map< std::string, unsigned int > & | getJointVariablesIndexMap () const |
Get the 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. Additionaly, it includes the names of the joints and the index for the first variable of that joint. | |
const LinkModel * | getLinkModel (const std::string &link) const |
Get a link by its name. | |
const std::vector< std::string > & | getLinkModelNames () const |
Get the link names (of all links) | |
const std::vector< std::string > & | getLinkModelNamesWithCollisionGeometry () const |
Get the names of the link models that have some collision geometry associated to themselves. | |
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< LinkModel * > & | getLinkModelsWithCollisionGeometry () const |
Get the link models that have some collision geometry associated to themselves. | |
const std::string & | getModelFrame () const |
Get the frame in which the transforms for this model are computed (when using a planning_models::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 (immediate descendant of the root joint) | |
const std::string & | getName () const |
Get the model name. | |
const JointModel * | getRoot () const |
Get the root joint. There will always be one root joint. This is either extracted from the SRDF, or a fixed joint is assumed, if no specification is given. | |
const std::string & | getRootJointName () const |
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. | |
const boost::shared_ptr< const srdf::Model > & | getSRDF () const |
Get the parsed SRDF model. | |
const boost::shared_ptr< const urdf::ModelInterface > & | getURDF () const |
Get the parsed URDF model. | |
unsigned int | getVariableCount () const |
Get the number of variables that describe this model. | |
void | getVariableDefaultValues (std::vector< double > &values) const |
Compute the default values for a RobotState. | |
void | getVariableDefaultValues (std::map< std::string, double > &values) const |
Compute the default values for a RobotState. | |
const std::vector< std::string > & | getVariableNames () const |
Get the names of the variables that make up the joints that form this state. Only active joints (not fixed, not mimic) are included. Effectively, these are the names of the DOF for this group. The number of returned elements is always equal to getVariableCount() | |
void | getVariableRandomValues (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values) const |
Compute the random values for a RobotState. | |
void | getVariableRandomValues (random_numbers::RandomNumberGenerator &rng, std::map< std::string, double > &values) const |
Compute the random values for a RobotState. | |
bool | hasEndEffector (const std::string &eef) const |
Check if an end effector exists. | |
bool | hasJointModel (const std::string &name) const |
Check if a joint exists. | |
bool | hasJointModelGroup (const std::string &group) const |
Check if the JointModelGroup group exists. | |
bool | hasLinkModel (const std::string &name) const |
Check if a link exists. | |
void | printModelInfo (std::ostream &out=std::cout) const |
Print information about the constructed model. | |
RobotModel (const boost::shared_ptr< const urdf::ModelInterface > &urdf_model, const boost::shared_ptr< const srdf::Model > &srdf_model) | |
Construct a kinematic model from a parsed description and a list of planning groups. | |
void | setKinematicsAllocators (const std::map< std::string, SolverAllocatorFn > &allocators) |
A map of known kinematics solvers (associated to their group name) | |
virtual | ~RobotModel () |
Destructor. Clear all memory. | |
Protected Types | |
typedef std::map< LinkModel *, Eigen::Affine3d, std::less < LinkModel * > , Eigen::aligned_allocator < std::pair< const LinkModel *, Eigen::Affine3d > > > | LinkModelToAffine3dMap |
Protected Member Functions | |
bool | addJointModelGroup (const srdf::Model::Group &group) |
Construct a JointModelGroup given a SRDF description group. | |
void | buildGroups (const srdf::Model &srdf_model) |
Given a SRDF model describing the groups, build up the groups in this kinematic model. | |
void | buildGroupsInfo_EndEffectors (const srdf::Model &srdf_model) |
Compute helpful information about groups (that can be queried later) | |
void | buildGroupsInfo_Subgroups (const srdf::Model &srdf_model) |
Compute helpful information about groups (that can be queried later) | |
void | buildGroupStates (const srdf::Model &srdf_model) |
Given a SRDF model describing the groups, build the default states defined in the SRDF. | |
void | buildJointInfo () |
Compute helpful information about joints. | |
void | buildMimic (const urdf::ModelInterface &urdf_model) |
Given the URDF model, build up the mimic joints (mutually constrained joints) | |
void | buildModel (const urdf::ModelInterface &urdf_model, const srdf::Model &srdf_model) |
Given an URDF model and a SRDF model, build a full kinematic model. | |
JointModel * | buildRecursive (LinkModel *parent, const urdf::Link *link, const srdf::Model &srdf_model) |
(This function is mostly intended for internal use). Given a parent link, build up (recursively), the kinematic model by walking down the tree | |
void | computeFixedTransforms (LinkModel *link, const Eigen::Affine3d &transform, LinkModelToAffine3dMap &associated_transforms) |
JointModel * | constructJointModel (const urdf::Joint *urdf_joint_model, const urdf::Link *child_link, const srdf::Model &srdf_model) |
Given a urdf joint model, a child link and a set of virtual joints, build up the corresponding JointModel object. | |
LinkModel * | constructLinkModel (const urdf::Link *urdf_link) |
Given a urdf link, build the corresponding LinkModel object. | |
shapes::ShapePtr | constructShape (const urdf::Geometry *geom) |
Given a geometry spec from the URDF and a filename (for a mesh), construct the corresponding shape object. | |
Protected Attributes | |
std::vector< std::string > | active_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::vector< const JointModel * > | continuous_joint_model_vector_const_ |
The set of continuous joints this model contains. | |
std::map< std::string, JointModelGroup * > | end_effectors_ |
The known end effectors. | |
std::map< std::string, srdf::Model::Group > | joint_model_group_config_map_ |
A map of all group names. | |
std::map< std::string, JointModelGroup * > | joint_model_group_map_ |
A map from group names to joint groups. | |
std::vector< std::string > | joint_model_group_names_ |
A vector of all group names. | |
std::map< std::string, JointModel * > | joint_model_map_ |
A map from joint names to their instances. | |
std::vector< std::string > | joint_model_names_vector_ |
The vector of joint names that corresponds to joint_model_vector_. | |
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::map< std::string, unsigned int > | 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. Additionaly, it includes the names of the joints and the index for the first variable of that joint. | |
std::map< std::string, LinkModel * > | link_model_map_ |
A map from link names to their instances. | |
std::vector< std::string > | link_model_names_vector_ |
The vector of link names that corresponds to link_model_vector_. | |
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::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< LinkModel * > | link_models_with_collision_geometry_vector_ |
Only links that have collision geometry specified. | |
std::string | model_frame_ |
The reference frame for this model. | |
std::string | model_name_ |
The name of the model. | |
JointModel * | root_joint_ |
The root joint. | |
LinkModel * | root_link_ |
The first physical link for the robot. | |
boost::shared_ptr< const srdf::Model > | srdf_ |
boost::shared_ptr< const urdf::ModelInterface > | urdf_ |
std::map< std::string, std::pair< double, double > > | variable_bounds_ |
The bounds for all the variables that make up the joints in this model. | |
unsigned int | variable_count_ |
Get the number of variables necessary to describe this model. |
Definition of a kinematic model. This class is not thread safe, however multiple instances can be created.
Definition at line 65 of file robot_model.h.
typedef std::map<LinkModel*, Eigen::Affine3d, std::less<LinkModel*>, Eigen::aligned_allocator<std::pair<const LinkModel*, Eigen::Affine3d> > > robot_model::RobotModel::LinkModelToAffine3dMap [protected] |
Definition at line 307 of file robot_model.h.
robot_model::RobotModel::RobotModel | ( | const boost::shared_ptr< const urdf::ModelInterface > & | urdf_model, |
const boost::shared_ptr< const srdf::Model > & | srdf_model | ||
) |
Construct a kinematic model from a parsed description and a list of planning groups.
Definition at line 48 of file robot_model.cpp.
robot_model::RobotModel::~RobotModel | ( | ) | [virtual] |
Destructor. Clear all memory.
Definition at line 57 of file robot_model.cpp.
bool robot_model::RobotModel::addJointModelGroup | ( | const srdf::Model::Group & | group | ) | [protected] |
Construct a JointModelGroup given a SRDF description group.
Definition at line 436 of file robot_model.cpp.
void robot_model::RobotModel::buildGroups | ( | const srdf::Model & | srdf_model | ) | [protected] |
Given a SRDF model describing the groups, build up the groups in this kinematic model.
Definition at line 294 of file robot_model.cpp.
void robot_model::RobotModel::buildGroupsInfo_EndEffectors | ( | const srdf::Model & | srdf_model | ) | [protected] |
Compute helpful information about groups (that can be queried later)
Definition at line 362 of file robot_model.cpp.
void robot_model::RobotModel::buildGroupsInfo_Subgroups | ( | const srdf::Model & | srdf_model | ) | [protected] |
Compute helpful information about groups (that can be queried later)
Definition at line 336 of file robot_model.cpp.
void robot_model::RobotModel::buildGroupStates | ( | const srdf::Model & | srdf_model | ) | [protected] |
Given a SRDF model describing the groups, build the default states defined in the SRDF.
Definition at line 153 of file robot_model.cpp.
void robot_model::RobotModel::buildJointInfo | ( | ) | [protected] |
Compute helpful information about joints.
Definition at line 99 of file robot_model.cpp.
void robot_model::RobotModel::buildMimic | ( | const urdf::ModelInterface & | urdf_model | ) | [protected] |
Given the URDF model, build up the mimic joints (mutually constrained joints)
Definition at line 183 of file robot_model.cpp.
void robot_model::RobotModel::buildModel | ( | const urdf::ModelInterface & | urdf_model, |
const srdf::Model & | srdf_model | ||
) | [protected] |
Given an URDF model and a SRDF model, build a full kinematic model.
Definition at line 67 of file robot_model.cpp.
robot_model::JointModel * robot_model::RobotModel::buildRecursive | ( | LinkModel * | parent, |
const urdf::Link * | link, | ||
const srdf::Model & | srdf_model | ||
) | [protected] |
(This function is mostly intended for internal use). Given a parent link, build up (recursively), the kinematic model by walking down the tree
Definition at line 558 of file robot_model.cpp.
void robot_model::RobotModel::computeFixedTransforms | ( | LinkModel * | link, |
const Eigen::Affine3d & | transform, | ||
LinkModelToAffine3dMap & | associated_transforms | ||
) | [protected] |
Definition at line 1156 of file robot_model.cpp.
robot_model::JointModel * robot_model::RobotModel::constructJointModel | ( | const urdf::Joint * | urdf_joint_model, |
const urdf::Link * | child_link, | ||
const srdf::Model & | srdf_model | ||
) | [protected] |
Given a urdf joint model, a child link and a set of virtual joints, build up the corresponding JointModel object.
Definition at line 605 of file robot_model.cpp.
robot_model::LinkModel * robot_model::RobotModel::constructLinkModel | ( | const urdf::Link * | urdf_link | ) | [protected] |
Given a urdf link, build the corresponding LinkModel object.
Definition at line 757 of file robot_model.cpp.
shapes::ShapePtr robot_model::RobotModel::constructShape | ( | const urdf::Geometry * | geom | ) | [protected] |
Given a geometry spec from the URDF and a filename (for a mesh), construct the corresponding shape object.
Definition at line 827 of file robot_model.cpp.
const std::map<std::string, std::pair<double, double> >& robot_model::RobotModel::getAllVariableBounds | ( | ) | const [inline] |
Get bounds for all the variables in this model. Bounds are returned as a std::pair<lower,upper>
Definition at line 287 of file robot_model.h.
std::vector< std::string > robot_model::RobotModel::getChildJointModelNames | ( | const LinkModel * | parent | ) | const |
Get the set of joint names that follow a parent link in the kinematic chain.
Definition at line 993 of file robot_model.cpp.
std::vector< std::string > robot_model::RobotModel::getChildJointModelNames | ( | const JointModel * | parent | ) | const |
Get the set of joint names that follow a parent joint in the kinematic chain.
Definition at line 1003 of file robot_model.cpp.
void robot_model::RobotModel::getChildJointModels | ( | const LinkModel * | parent, |
std::vector< const JointModel * > & | links | ||
) | const |
Get the set of joint models that follow a parent link in the kinematic chain.
Definition at line 942 of file robot_model.cpp.
void robot_model::RobotModel::getChildJointModels | ( | const JointModel * | parent, |
std::vector< const JointModel * > & | links | ||
) | const |
Get the set of joint models that follow a parent joint in the kinematic chain.
Definition at line 967 of file robot_model.cpp.
std::vector< std::string > robot_model::RobotModel::getChildLinkModelNames | ( | const LinkModel * | parent | ) | const |
Get the set of link names that follow a parent link in the kinematic chain.
Definition at line 973 of file robot_model.cpp.
std::vector< std::string > robot_model::RobotModel::getChildLinkModelNames | ( | const JointModel * | parent | ) | const |
Get the set of link names that follow a parent link in the kinematic chain.
Definition at line 983 of file robot_model.cpp.
void robot_model::RobotModel::getChildLinkModels | ( | const LinkModel * | parent, |
std::vector< const LinkModel * > & | links | ||
) | const |
Get the set of link models that follow a parent link in the kinematic chain.
Definition at line 912 of file robot_model.cpp.
void robot_model::RobotModel::getChildLinkModels | ( | const JointModel * | parent, |
std::vector< const LinkModel * > & | links | ||
) | const |
Get the set of link models that follow a parent joint in the kinematic chain.
Definition at line 937 of file robot_model.cpp.
const std::vector<const JointModel*>& robot_model::RobotModel::getContinuousJointModels | ( | ) | const [inline] |
Get the array of continuous joints, in the order they appear in the robot state.
Definition at line 152 of file robot_model.h.
const robot_model::JointModelGroup * robot_model::RobotModel::getEndEffector | ( | const std::string & | name | ) | const |
Get the joint group that corresponds to a given end-effector name.
Definition at line 239 of file robot_model.cpp.
robot_model::JointModelGroup * robot_model::RobotModel::getEndEffector | ( | const std::string & | name | ) |
Get the joint group that corresponds to a given end-effector name.
Definition at line 253 of file robot_model.cpp.
const std::map<std::string, JointModelGroup*>& robot_model::RobotModel::getEndEffectorsMap | ( | ) | const [inline] |
Get the map between end effector names and the groups they correspond to.
Definition at line 267 of file robot_model.h.
const robot_model::JointModel * robot_model::RobotModel::getJointModel | ( | const std::string & | joint | ) | const |
Get a joint by its name.
Definition at line 888 of file robot_model.cpp.
const robot_model::JointModelGroup * robot_model::RobotModel::getJointModelGroup | ( | const std::string & | name | ) | const |
Get a joint group from this model (by name)
Definition at line 272 of file robot_model.cpp.
robot_model::JointModelGroup * robot_model::RobotModel::getJointModelGroup | ( | const std::string & | name | ) |
Get a joint group from this model (by name)
Definition at line 283 of file robot_model.cpp.
const std::map<std::string, srdf::Model::Group>& robot_model::RobotModel::getJointModelGroupConfigMap | ( | ) | const [inline] |
Get the map between joint group names and the SRDF group object.
Definition at line 252 of file robot_model.h.
const std::map<std::string, JointModelGroup*>& robot_model::RobotModel::getJointModelGroupMap | ( | ) | const [inline] |
Get the map between joint group names and the groups.
Definition at line 240 of file robot_model.h.
const std::vector<std::string>& robot_model::RobotModel::getJointModelGroupNames | ( | ) | const [inline] |
Get the names of all groups that are defined for this model.
Definition at line 246 of file robot_model.h.
const std::vector<std::string>& robot_model::RobotModel::getJointModelNames | ( | ) | const [inline] |
Get the array of joint names, in the order they appear in the robot state.
Definition at line 145 of file robot_model.h.
const std::vector<const JointModel*>& robot_model::RobotModel::getJointModels | ( | ) | const [inline] |
Get the array of joints, in the order they appear in the robot state.
Definition at line 132 of file robot_model.h.
const std::vector<JointModel*>& robot_model::RobotModel::getJointModels | ( | ) | [inline] |
Get the array of joints, in the order they appear in the robot state.
Definition at line 139 of file robot_model.h.
const std::map<std::string, unsigned int>& robot_model::RobotModel::getJointVariablesIndexMap | ( | ) | const [inline] |
Get the 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. Additionaly, it includes the names of the joints and the index for the first variable of that joint.
Definition at line 296 of file robot_model.h.
const robot_model::LinkModel * robot_model::RobotModel::getLinkModel | ( | const std::string & | link | ) | const |
Get a link by its name.
Definition at line 900 of file robot_model.cpp.
const std::vector<std::string>& robot_model::RobotModel::getLinkModelNames | ( | ) | const [inline] |
Get the link names (of all links)
Definition at line 170 of file robot_model.h.
const std::vector<std::string>& robot_model::RobotModel::getLinkModelNamesWithCollisionGeometry | ( | ) | const [inline] |
Get the names of the link models that have some collision geometry associated to themselves.
Definition at line 182 of file robot_model.h.
const std::vector<const LinkModel*>& robot_model::RobotModel::getLinkModels | ( | ) | const [inline] |
Get the array of links.
Definition at line 158 of file robot_model.h.
const std::vector<LinkModel*>& robot_model::RobotModel::getLinkModels | ( | ) | [inline] |
Get the array of links.
Definition at line 164 of file robot_model.h.
const std::vector<LinkModel*>& robot_model::RobotModel::getLinkModelsWithCollisionGeometry | ( | ) | const [inline] |
Get the link models that have some collision geometry associated to themselves.
Definition at line 176 of file robot_model.h.
const std::string& robot_model::RobotModel::getModelFrame | ( | ) | const [inline] |
Get the frame in which the transforms for this model are computed (when using a planning_models::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 (immediate descendant of the root joint)
Definition at line 210 of file robot_model.h.
const std::string& robot_model::RobotModel::getName | ( | ) | const [inline] |
Get the model name.
Definition at line 77 of file robot_model.h.
const JointModel* robot_model::RobotModel::getRoot | ( | ) | const [inline] |
Get the root joint. There will always be one root joint. This is either extracted from the SRDF, or a fixed joint is assumed, if no specification is given.
Definition at line 190 of file robot_model.h.
const std::string & robot_model::RobotModel::getRootJointName | ( | ) | const |
Definition at line 866 of file robot_model.cpp.
const LinkModel* robot_model::RobotModel::getRootLink | ( | ) | const [inline] |
Get the physical root link of the robot.
Definition at line 198 of file robot_model.h.
const std::string & robot_model::RobotModel::getRootLinkName | ( | ) | const |
Get the name of the root link of the robot.
Definition at line 872 of file robot_model.cpp.
const boost::shared_ptr<const srdf::Model>& robot_model::RobotModel::getSRDF | ( | ) | const [inline] |
Get the parsed SRDF model.
Definition at line 89 of file robot_model.h.
const boost::shared_ptr<const urdf::ModelInterface>& robot_model::RobotModel::getURDF | ( | ) | const [inline] |
Get the parsed URDF model.
Definition at line 83 of file robot_model.h.
unsigned int robot_model::RobotModel::getVariableCount | ( | ) | const [inline] |
Get the number of variables that describe this model.
Definition at line 273 of file robot_model.h.
void robot_model::RobotModel::getVariableDefaultValues | ( | std::vector< double > & | values | ) | const |
Compute the default values for a RobotState.
Definition at line 1028 of file robot_model.cpp.
void robot_model::RobotModel::getVariableDefaultValues | ( | std::map< std::string, double > & | values | ) | const |
Compute the default values for a RobotState.
Definition at line 1035 of file robot_model.cpp.
const std::vector<std::string>& robot_model::RobotModel::getVariableNames | ( | ) | const [inline] |
Get the names of the variables that make up the joints that form this state. Only active joints (not fixed, not mimic) are included. Effectively, these are the names of the DOF for this group. The number of returned elements is always equal to getVariableCount()
Definition at line 281 of file robot_model.h.
void robot_model::RobotModel::getVariableRandomValues | ( | random_numbers::RandomNumberGenerator & | rng, |
std::vector< double > & | values | ||
) | const |
Compute the random values for a RobotState.
Definition at line 1014 of file robot_model.cpp.
void robot_model::RobotModel::getVariableRandomValues | ( | random_numbers::RandomNumberGenerator & | rng, |
std::map< std::string, double > & | values | ||
) | const |
Compute the random values for a RobotState.
Definition at line 1021 of file robot_model.cpp.
bool robot_model::RobotModel::hasEndEffector | ( | const std::string & | eef | ) | const |
Check if an end effector exists.
Definition at line 234 of file robot_model.cpp.
bool robot_model::RobotModel::hasJointModel | ( | const std::string & | name | ) | const |
Check if a joint exists.
Definition at line 878 of file robot_model.cpp.
bool robot_model::RobotModel::hasJointModelGroup | ( | const std::string & | group | ) | const |
Check if the JointModelGroup group exists.
Definition at line 267 of file robot_model.cpp.
bool robot_model::RobotModel::hasLinkModel | ( | const std::string & | name | ) | const |
Check if a link exists.
Definition at line 883 of file robot_model.cpp.
void robot_model::RobotModel::printModelInfo | ( | std::ostream & | out = std::cout | ) | const |
Print information about the constructed model.
Definition at line 1098 of file robot_model.cpp.
void robot_model::RobotModel::setKinematicsAllocators | ( | const std::map< std::string, SolverAllocatorFn > & | allocators | ) |
A map of known kinematics solvers (associated to their group name)
Definition at line 1042 of file robot_model.cpp.
std::vector<std::string> robot_model::RobotModel::active_variable_names_ [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 351 of file robot_model.h.
std::vector<const JointModel*> robot_model::RobotModel::continuous_joint_model_vector_const_ [protected] |
The set of continuous joints this model contains.
Definition at line 348 of file robot_model.h.
std::map<std::string, JointModelGroup*> robot_model::RobotModel::end_effectors_ [protected] |
The known end effectors.
Definition at line 381 of file robot_model.h.
std::map<std::string, srdf::Model::Group> robot_model::RobotModel::joint_model_group_config_map_ [protected] |
A map of all group names.
Definition at line 378 of file robot_model.h.
std::map<std::string, JointModelGroup*> robot_model::RobotModel::joint_model_group_map_ [protected] |
A map from group names to joint groups.
Definition at line 372 of file robot_model.h.
std::vector<std::string> robot_model::RobotModel::joint_model_group_names_ [protected] |
A vector of all group names.
Definition at line 375 of file robot_model.h.
std::map<std::string, JointModel*> robot_model::RobotModel::joint_model_map_ [protected] |
A map from joint names to their instances.
Definition at line 336 of file robot_model.h.
std::vector<std::string> robot_model::RobotModel::joint_model_names_vector_ [protected] |
The vector of joint names that corresponds to joint_model_vector_.
Definition at line 345 of file robot_model.h.
std::vector<JointModel*> robot_model::RobotModel::joint_model_vector_ [protected] |
The vector of joints in the model, in the order they appear in the state vector.
Definition at line 339 of file robot_model.h.
std::vector<const JointModel*> robot_model::RobotModel::joint_model_vector_const_ [protected] |
The vector of joints in the model, in the order they appear in the state vector.
Definition at line 342 of file robot_model.h.
std::map<std::string, unsigned int> robot_model::RobotModel::joint_variables_index_map_ [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. Additionaly, it includes the names of the joints and the index for the first variable of that joint.
Definition at line 363 of file robot_model.h.
std::map<std::string, LinkModel*> robot_model::RobotModel::link_model_map_ [protected] |
A map from link names to their instances.
Definition at line 318 of file robot_model.h.
std::vector<std::string> robot_model::RobotModel::link_model_names_vector_ [protected] |
The vector of link names that corresponds to link_model_vector_.
Definition at line 327 of file robot_model.h.
std::vector<std::string> robot_model::RobotModel::link_model_names_with_collision_geometry_vector_ [protected] |
The vector of link names that corresponds to link_models_with_collision_geometry_vector_.
Definition at line 333 of file robot_model.h.
std::vector<LinkModel*> robot_model::RobotModel::link_model_vector_ [protected] |
The vector of links that are updated when computeTransforms() is called, in the order they are updated.
Definition at line 321 of file robot_model.h.
std::vector<const LinkModel*> robot_model::RobotModel::link_model_vector_const_ [protected] |
The vector of links that are updated when computeTransforms() is called, in the order they are updated.
Definition at line 324 of file robot_model.h.
std::vector<LinkModel*> robot_model::RobotModel::link_models_with_collision_geometry_vector_ [protected] |
Only links that have collision geometry specified.
Definition at line 330 of file robot_model.h.
std::string robot_model::RobotModel::model_frame_ [protected] |
The reference frame for this model.
Definition at line 315 of file robot_model.h.
std::string robot_model::RobotModel::model_name_ [protected] |
The name of the model.
Definition at line 312 of file robot_model.h.
JointModel* robot_model::RobotModel::root_joint_ [protected] |
The root joint.
Definition at line 366 of file robot_model.h.
LinkModel* robot_model::RobotModel::root_link_ [protected] |
The first physical link for the robot.
Definition at line 369 of file robot_model.h.
boost::shared_ptr<const srdf::Model> robot_model::RobotModel::srdf_ [protected] |
Definition at line 383 of file robot_model.h.
boost::shared_ptr<const urdf::ModelInterface> robot_model::RobotModel::urdf_ [protected] |
Definition at line 385 of file robot_model.h.
std::map<std::string, std::pair<double, double> > robot_model::RobotModel::variable_bounds_ [protected] |
The bounds for all the variables that make up the joints in this model.
Definition at line 358 of file robot_model.h.
unsigned int robot_model::RobotModel::variable_count_ [protected] |
Get the number of variables necessary to describe this model.
Definition at line 354 of file robot_model.h.