Public Member Functions | Protected Member Functions | Protected Attributes
moveit::core::RobotModel Class Reference

Definition of a kinematic model. This class is not thread safe, however multiple instances can be created. More...

#include <robot_model.h>

List of all members.

Public Member Functions

double distance (const double *state1, const double *state2) const
bool enforcePositionBounds (double *state) const
bool enforcePositionBounds (double *state, const JointBoundsVector &active_joint_bounds) const
const JointBoundsVectorgetActiveJointModelsBounds () const
 Get the bounds for all the active joints.
const JointModelgetCommonRoot (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.
double getMaximumExtent () const
double getMaximumExtent (const JointBoundsVector &active_joint_bounds) const
void getMissingVariableNames (const std::vector< std::string > &variables, std::vector< std::string > &missing_variables) const
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.
const std::string & getName () const
 Get the model name.
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.
const VariableBoundsgetVariableBounds (const std::string &variable) const
 Get the bounds for a specific variable. Throw an exception of variable is not found.
std::size_t getVariableCount () const
 Get the number of variables that describe this model.
void getVariableDefaultPositions (double *values) const
 Compute the default values for a RobotState.
void getVariableDefaultPositions (std::vector< double > &values) const
 Compute the default values for a RobotState.
void getVariableDefaultPositions (std::map< std::string, double > &values) const
 Compute the default values for a RobotState.
int getVariableIndex (const std::string &variable) const
 Get the index of a variable in the robot state.
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()
void getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, double *values) const
 Compute the random values for a RobotState.
void getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values) const
 Compute the random 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 interpolate (const double *from, const double *to, double t, double *state) const
bool isEmpty () const
 Return true if the model is empty (has no root link, no joints)
void printModelInfo (std::ostream &out) 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.
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
void setKinematicsAllocators (const std::map< std::string, SolverAllocatorFn > &allocators)
 A map of known kinematics solvers (associated to their group name)
 ~RobotModel ()
 Destructor. Clear all memory.
Access to joint models
const JointModelgetRootJoint () 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 JointModelgetJointModel (const std::string &joint) const
 Get a joint by its name. Output error and return NULL when the joint is missing.
const JointModelgetJointModel (int index) const
 Get a joint by its index. Output error and return NULL when the link is missing.
JointModelgetJointModel (const std::string &joint)
 Get a joint by its name. Output error and return NULL 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< 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 JointModelgetJointOfVariable (int variable_index) const
const JointModelgetJointOfVariable (const std::string &variable) const
std::size_t getJointModelCount () const
Access to link models
const LinkModelgetRootLink () 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 LinkModelgetLinkModel (const std::string &link) const
 Get a link by its name. Output error and return NULL when the link is missing.
const LinkModelgetLinkModel (int index) const
 Get a link by its index. Output error and return NULL when the link is missing.
LinkModelgetLinkModel (const std::string &link)
 Get a link by its name. Output error and return NULL 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
Access to joint groups
bool hasJointModelGroup (const std::string &group) const
 Check if the JointModelGroup group exists.
const JointModelGroupgetJointModelGroup (const std::string &name) const
 Get a joint group from this model (by name)
JointModelGroupgetJointModelGroup (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 JointModelGroupgetEndEffector (const std::string &name) const
 Get the joint group that corresponds to a given end-effector name.
JointModelGroupgetEndEffector (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

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.
JointModelbuildRecursive (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
const JointModelcomputeCommonRoot (const JointModel *a, const JointModel *b) const
 Given two joints, find their common root.
void computeCommonRoots ()
 For every pair of joints, pre-compute the common roots of the joints.
void computeDescendants ()
 For every joint, pre-compute the list of descendant joints & links.
void computeFixedTransforms (const LinkModel *link, const Eigen::Affine3d &transform, LinkTransformMap &associated_transforms)
JointModelconstructJointModel (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.
LinkModelconstructLinkModel (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.
void updateMimicJoints (double *values) const
 Update the variable values for the state of a group with respect to the mimic joints.

Protected Attributes

std::vector< int > active_joint_model_start_index_
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< const JointModel * > active_joint_model_vector_const_
 The vector of joints in the model, in the order they appear in the state vector.
JointBoundsVector active_joint_models_bounds_
 The bounds for all the active joint models.
std::vector< int > common_joint_roots_
 For every two joints, the index of the common root for thw joints is stored.
std::vector< const JointModel * > continuous_joint_model_vector_
 The set of continuous joints this model contains.
std::vector< const
JointModelGroup * > 
end_effectors_
 The array of end-effectors, in alphabetical order.
JointModelGroupMap end_effectors_map_
 The known end effectors.
JointModelGroupMap 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, in alphabetical order.
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.
JointModelMap 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.
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. Additionaly, it includes the names of the joints and the index for the first variable of that joint.
std::vector< const JointModel * > joints_of_variable_
 The joints that correspond to each variable index.
std::size_t link_geometry_count_
 Total number of geometric shapes in this model.
LinkModelMap 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< const LinkModel * > link_models_with_collision_geometry_vector_
 Only links that have collision geometry specified.
std::vector< const JointModel * > mimic_joints_
 The set of mimic joints this model contains.
std::string model_frame_
 The reference frame for this model.
std::string model_name_
 The name of the model.
std::vector< const JointModel * > multi_dof_joints_
const JointModelroot_joint_
 The root joint.
const LinkModelroot_link_
 The first physical link for the robot.
std::vector< const JointModel * > single_dof_joints_
boost::shared_ptr< const
srdf::Model
srdf_
boost::shared_ptr< const
urdf::ModelInterface > 
urdf_
std::size_t variable_count_
 Get the number of variables necessary to describe this model.
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!)

Detailed Description

Definition of a kinematic model. This class is not thread safe, however multiple instances can be created.

Definition at line 68 of file robot_model.h.


Constructor & Destructor Documentation

moveit::core::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 50 of file robot_model.cpp.

Destructor. Clear all memory.

Definition at line 59 of file robot_model.cpp.


Member Function Documentation

Construct a JointModelGroup given a SRDF description group.

Definition at line 643 of file robot_model.cpp.

void moveit::core::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 480 of file robot_model.cpp.

void moveit::core::RobotModel::buildGroupsInfo_EndEffectors ( const srdf::Model srdf_model) [protected]

Compute helpful information about groups (that can be queried later)

Definition at line 560 of file robot_model.cpp.

void moveit::core::RobotModel::buildGroupsInfo_Subgroups ( const srdf::Model srdf_model) [protected]

Compute helpful information about groups (that can be queried later)

Definition at line 531 of file robot_model.cpp.

void moveit::core::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 321 of file robot_model.cpp.

Compute helpful information about joints.

Definition at line 251 of file robot_model.cpp.

void moveit::core::RobotModel::buildMimic ( const urdf::ModelInterface &  urdf_model) [protected]

Given the URDF model, build up the mimic joints (mutually constrained joints)

Definition at line 360 of file robot_model.cpp.

void moveit::core::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 79 of file robot_model.cpp.

moveit::core::JointModel * moveit::core::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 758 of file robot_model.cpp.

const JointModel* moveit::core::RobotModel::computeCommonRoot ( const JointModel a,
const JointModel b 
) const [protected]

Given two joints, find their common root.

For every pair of joints, pre-compute the common roots of the joints.

Definition at line 199 of file robot_model.cpp.

For every joint, pre-compute the list of descendant joints & links.

Definition at line 232 of file robot_model.cpp.

void moveit::core::RobotModel::computeFixedTransforms ( const LinkModel link,
const Eigen::Affine3d &  transform,
LinkTransformMap associated_transforms 
) [protected]

Definition at line 1377 of file robot_model.cpp.

moveit::core::JointModel * moveit::core::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 844 of file robot_model.cpp.

moveit::core::LinkModel * moveit::core::RobotModel::constructLinkModel ( const urdf::Link *  urdf_link) [protected]

Given a urdf link, build the corresponding LinkModel object.

Definition at line 964 of file robot_model.cpp.

shapes::ShapePtr moveit::core::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 1032 of file robot_model.cpp.

double moveit::core::RobotModel::distance ( const double *  state1,
const double *  state2 
) const

Definition at line 1236 of file robot_model.cpp.

bool moveit::core::RobotModel::enforcePositionBounds ( double *  state) const [inline]

Definition at line 312 of file robot_model.h.

bool moveit::core::RobotModel::enforcePositionBounds ( double *  state,
const JointBoundsVector active_joint_bounds 
) const

Definition at line 1223 of file robot_model.cpp.

const std::vector<const JointModel*>& moveit::core::RobotModel::getActiveJointModels ( ) const [inline]

Get the array of joints that are active (not fixed, not mimic) in this model.

Definition at line 164 of file robot_model.h.

Get the array of joints that are active (not fixed, not mimic) in this model.

Definition at line 170 of file robot_model.h.

Get the bounds for all the active joints.

Definition at line 402 of file robot_model.h.

const JointModel* moveit::core::RobotModel::getCommonRoot ( const JointModel a,
const JointModel b 
) const [inline]

Get the deepest joint in the kinematic tree that is a common parent of both joints passed as argument.

Definition at line 414 of file robot_model.h.

const std::vector<const JointModel*>& moveit::core::RobotModel::getContinuousJointModels ( ) const [inline]

Get the array of continuous joints, in the order they appear in the robot state.

Definition at line 189 of file robot_model.h.

const moveit::core::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 425 of file robot_model.cpp.

Get the joint group that corresponds to a given end-effector name.

Definition at line 439 of file robot_model.cpp.

const std::vector<const JointModelGroup*>& moveit::core::RobotModel::getEndEffectors ( ) const [inline]

Get the map between end effector names and the groups they correspond to.

Definition at line 373 of file robot_model.h.

const moveit::core::JointModel * moveit::core::RobotModel::getJointModel ( const std::string &  joint) const

Get a joint by its name. Output error and return NULL when the joint is missing.

Definition at line 1081 of file robot_model.cpp.

Get a joint by its index. Output error and return NULL when the link is missing.

Definition at line 1090 of file robot_model.cpp.

Get a joint by its name. Output error and return NULL when the joint is missing.

Definition at line 1101 of file robot_model.cpp.

std::size_t moveit::core::RobotModel::getJointModelCount ( ) const [inline]

Definition at line 211 of file robot_model.h.

Get a joint group from this model (by name)

Definition at line 458 of file robot_model.cpp.

Get a joint group from this model (by name)

Definition at line 469 of file robot_model.cpp.

const std::vector<std::string>& moveit::core::RobotModel::getJointModelGroupNames ( ) const [inline]

Get the names of all groups that are defined for this model.

Definition at line 358 of file robot_model.h.

const std::vector<const JointModelGroup*>& moveit::core::RobotModel::getJointModelGroups ( ) const [inline]

Get the available joint groups.

Definition at line 346 of file robot_model.h.

Get the available joint groups.

Definition at line 352 of file robot_model.h.

const std::vector<std::string>& moveit::core::RobotModel::getJointModelNames ( ) const [inline]

Get the array of joint names, in the order they appear in the robot state.

Definition at line 158 of file robot_model.h.

const std::vector<const JointModel*>& moveit::core::RobotModel::getJointModels ( ) const [inline]

Get the array of joints, in the order they appear in the robot state.

Definition at line 144 of file robot_model.h.

const std::vector<JointModel*>& moveit::core::RobotModel::getJointModels ( ) [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 152 of file robot_model.h.

const JointModel* moveit::core::RobotModel::getJointOfVariable ( int  variable_index) const [inline]

Definition at line 201 of file robot_model.h.

const JointModel* moveit::core::RobotModel::getJointOfVariable ( const std::string &  variable) const [inline]

Definition at line 206 of file robot_model.h.

std::size_t moveit::core::RobotModel::getLinkGeometryCount ( ) const [inline]

Definition at line 278 of file robot_model.h.

const moveit::core::LinkModel * moveit::core::RobotModel::getLinkModel ( const std::string &  link) const

Get a link by its name. Output error and return NULL when the link is missing.

Definition at line 1110 of file robot_model.cpp.

Get a link by its index. Output error and return NULL when the link is missing.

Definition at line 1119 of file robot_model.cpp.

Get a link by its name. Output error and return NULL when the link is missing.

Definition at line 1130 of file robot_model.cpp.

std::size_t moveit::core::RobotModel::getLinkModelCount ( ) const [inline]

Definition at line 273 of file robot_model.h.

const std::vector<std::string>& moveit::core::RobotModel::getLinkModelNames ( ) const [inline]

Get the link names (of all links)

Definition at line 256 of file robot_model.h.

const std::vector<std::string>& moveit::core::RobotModel::getLinkModelNamesWithCollisionGeometry ( ) const [inline]

Get the names of the link models that have some collision geometry associated to themselves.

Definition at line 268 of file robot_model.h.

const std::vector<const LinkModel*>& moveit::core::RobotModel::getLinkModels ( ) const [inline]

Get the array of links.

Definition at line 244 of file robot_model.h.

const std::vector<LinkModel*>& moveit::core::RobotModel::getLinkModels ( ) [inline]

Get the array of links.

Definition at line 250 of file robot_model.h.

const std::vector<const LinkModel*>& moveit::core::RobotModel::getLinkModelsWithCollisionGeometry ( ) const [inline]

Get the link models that have some collision geometry associated to themselves.

Definition at line 262 of file robot_model.h.

double moveit::core::RobotModel::getMaximumExtent ( ) const [inline]

Definition at line 323 of file robot_model.h.

double moveit::core::RobotModel::getMaximumExtent ( const JointBoundsVector active_joint_bounds) const

Definition at line 1202 of file robot_model.cpp.

const std::vector<const JointModel*>& moveit::core::RobotModel::getMimicJointModels ( ) const [inline]

Get the array of mimic joints, in the order they appear in the robot state.

Definition at line 196 of file robot_model.h.

void moveit::core::RobotModel::getMissingVariableNames ( const std::vector< std::string > &  variables,
std::vector< std::string > &  missing_variables 
) const

Definition at line 1183 of file robot_model.cpp.

const std::string& moveit::core::RobotModel::getModelFrame ( ) 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 88 of file robot_model.h.

const std::vector<const JointModel*>& moveit::core::RobotModel::getMultiDOFJointModels ( ) const [inline]

This is a list of all multi-dof joints.

Definition at line 182 of file robot_model.h.

const std::string& moveit::core::RobotModel::getName ( ) const [inline]

Get the model name.

Definition at line 79 of file robot_model.h.

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 69 of file robot_model.cpp.

const std::string& moveit::core::RobotModel::getRootJointName ( ) const [inline]

Return the name of the root joint. Throws an exception if there is no root joint.

Definition at line 125 of file robot_model.h.

Get the physical root link of the robot.

Definition at line 74 of file robot_model.cpp.

const std::string& moveit::core::RobotModel::getRootLinkName ( ) const [inline]

Get the name of the root link of the robot.

Definition at line 226 of file robot_model.h.

const std::vector<const JointModel*>& moveit::core::RobotModel::getSingleDOFJointModels ( ) const [inline]

This is a list of all single-dof joints (including mimic joints)

Definition at line 176 of file robot_model.h.

const boost::shared_ptr<const srdf::Model>& moveit::core::RobotModel::getSRDF ( ) const [inline]

Get the parsed SRDF model.

Definition at line 106 of file robot_model.h.

const boost::shared_ptr<const urdf::ModelInterface>& moveit::core::RobotModel::getURDF ( ) const [inline]

Get the parsed URDF model.

Definition at line 100 of file robot_model.h.

const VariableBounds& moveit::core::RobotModel::getVariableBounds ( const std::string &  variable) const [inline]

Get the bounds for a specific variable. Throw an exception of variable is not found.

Definition at line 396 of file robot_model.h.

std::size_t moveit::core::RobotModel::getVariableCount ( ) const [inline]

Get the number of variables that describe this model.

Definition at line 381 of file robot_model.h.

Compute the default values for a RobotState.

Definition at line 1167 of file robot_model.cpp.

void moveit::core::RobotModel::getVariableDefaultPositions ( std::vector< double > &  values) const [inline]

Compute the default values for a RobotState.

Definition at line 299 of file robot_model.h.

void moveit::core::RobotModel::getVariableDefaultPositions ( std::map< std::string, double > &  values) const

Compute the default values for a RobotState.

Definition at line 1174 of file robot_model.cpp.

int moveit::core::RobotModel::getVariableIndex ( const std::string &  variable) const

Get the index of a variable in the robot state.

Definition at line 1194 of file robot_model.cpp.

const std::vector<std::string>& moveit::core::RobotModel::getVariableNames ( ) const [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 390 of file robot_model.h.

Compute the random values for a RobotState.

Definition at line 1149 of file robot_model.cpp.

void moveit::core::RobotModel::getVariableRandomPositions ( random_numbers::RandomNumberGenerator rng,
std::vector< double > &  values 
) const [inline]

Compute the random values for a RobotState.

Definition at line 292 of file robot_model.h.

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 1157 of file robot_model.cpp.

bool moveit::core::RobotModel::hasEndEffector ( const std::string &  eef) const

Check if an end effector exists.

Definition at line 420 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 1071 of file robot_model.cpp.

bool moveit::core::RobotModel::hasJointModelGroup ( const std::string &  group) const

Check if the JointModelGroup group exists.

Definition at line 453 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.

Definition at line 1076 of file robot_model.cpp.

void moveit::core::RobotModel::interpolate ( const double *  from,
const double *  to,
double  t,
double *  state 
) const

Definition at line 1246 of file robot_model.cpp.

bool moveit::core::RobotModel::isEmpty ( ) const [inline]

Return true if the model is empty (has no root link, no joints)

Definition at line 94 of file robot_model.h.

void moveit::core::RobotModel::printModelInfo ( std::ostream &  out) const

Print information about the constructed model.

Definition at line 1326 of file robot_model.cpp.

bool moveit::core::RobotModel::satisfiesPositionBounds ( const double *  state,
double  margin = 0.0 
) const [inline]

Definition at line 317 of file robot_model.h.

bool moveit::core::RobotModel::satisfiesPositionBounds ( const double *  state,
const JointBoundsVector active_joint_bounds,
double  margin = 0.0 
) const

Definition at line 1211 of file robot_model.cpp.

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 1257 of file robot_model.cpp.

void moveit::core::RobotModel::updateMimicJoints ( double *  values) const [protected]

Update the variable values for the state of a group with respect to the mimic joints.

Definition at line 1139 of file robot_model.cpp.


Member Data Documentation

Definition at line 531 of file robot_model.h.

The vector of joints in the model, in the order they appear in the state vector.

Definition at line 493 of file robot_model.h.

The vector of joints in the model, in the order they appear in the state vector.

Definition at line 496 of file robot_model.h.

The bounds for all the active joint models.

Definition at line 534 of file robot_model.h.

std::vector<int> moveit::core::RobotModel::common_joint_roots_ [protected]

For every two joints, the index of the common root for thw 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 515 of file robot_model.h.

The set of continuous joints this model contains.

Definition at line 499 of file robot_model.h.

The array of end-effectors, in alphabetical order.

Definition at line 557 of file robot_model.h.

The known end effectors.

Definition at line 545 of file robot_model.h.

A map from group names to joint groups.

Definition at line 542 of file robot_model.h.

std::vector<std::string> moveit::core::RobotModel::joint_model_group_names_ [protected]

A vector of all group names, in alphabetical order.

Definition at line 554 of file robot_model.h.

The array of joint model groups, in alphabetical order.

Definition at line 548 of file robot_model.h.

The array of joint model groups, in alphabetical order.

Definition at line 551 of file robot_model.h.

A map from joint names to their instances.

Definition at line 481 of file robot_model.h.

std::vector<std::string> moveit::core::RobotModel::joint_model_names_vector_ [protected]

The vector of joint names that corresponds to joint_model_vector_.

Definition at line 490 of file robot_model.h.

The vector of joints in the model, in the order they appear in the state vector.

Definition at line 484 of file robot_model.h.

The vector of joints in the model, in the order they appear in the state vector.

Definition at line 487 of file robot_model.h.

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 529 of file robot_model.h.

The joints that correspond to each variable index.

Definition at line 537 of file robot_model.h.

Total number of geometric shapes in this model.

Definition at line 473 of file robot_model.h.

A map from link names to their instances.

Definition at line 455 of file robot_model.h.

std::vector<std::string> moveit::core::RobotModel::link_model_names_vector_ [protected]

The vector of link names that corresponds to link_model_vector_.

Definition at line 464 of file robot_model.h.

The vector of link names that corresponds to link_models_with_collision_geometry_vector_.

Definition at line 470 of file robot_model.h.

The vector of links that are updated when computeTransforms() is called, in the order they are updated.

Definition at line 458 of file robot_model.h.

The vector of links that are updated when computeTransforms() is called, in the order they are updated.

Definition at line 461 of file robot_model.h.

Only links that have collision geometry specified.

Definition at line 467 of file robot_model.h.

std::vector<const JointModel*> moveit::core::RobotModel::mimic_joints_ [protected]

The set of mimic joints this model contains.

Definition at line 502 of file robot_model.h.

std::string moveit::core::RobotModel::model_frame_ [protected]

The reference frame for this model.

Definition at line 443 of file robot_model.h.

std::string moveit::core::RobotModel::model_name_ [protected]

The name of the model.

Definition at line 440 of file robot_model.h.

Definition at line 506 of file robot_model.h.

The root joint.

Definition at line 478 of file robot_model.h.

The first physical link for the robot.

Definition at line 452 of file robot_model.h.

Definition at line 504 of file robot_model.h.

boost::shared_ptr<const srdf::Model> moveit::core::RobotModel::srdf_ [protected]

Definition at line 445 of file robot_model.h.

boost::shared_ptr<const urdf::ModelInterface> moveit::core::RobotModel::urdf_ [protected]

Definition at line 447 of file robot_model.h.

Get the number of variables necessary to describe this model.

Definition at line 524 of file robot_model.h.

std::vector<std::string> moveit::core::RobotModel::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 521 of file robot_model.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Jul 24 2017 02:20:45