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 | |
double | distance (const double *state1, const double *state2) const |
Return the sum of joint distances between two states. Only considers active joints. More... | |
bool | enforcePositionBounds (double *state) const |
bool | enforcePositionBounds (double *state, const JointBoundsVector &active_joint_bounds) const |
const JointBoundsVector & | getActiveJointModelsBounds () const |
Get the bounds for all the active joints. More... | |
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. More... | |
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. More... | |
const std::string & | getName () const |
Get the model name. More... | |
const srdf::ModelConstSharedPtr & | getSRDF () const |
Get the parsed SRDF model. More... | |
const urdf::ModelInterfaceSharedPtr & | getURDF () const |
Get the parsed URDF model. More... | |
const VariableBounds & | getVariableBounds (const std::string &variable) const |
Get the bounds for a specific variable. Throw an exception of variable is not found. More... | |
std::size_t | getVariableCount () const |
Get the number of variables that describe this model. More... | |
void | getVariableDefaultPositions (double *values) const |
Compute the default values for a RobotState. More... | |
void | getVariableDefaultPositions (std::map< std::string, double > &values) const |
Compute the default values for a RobotState. More... | |
void | getVariableDefaultPositions (std::vector< double > &values) const |
Compute the default values for a RobotState. More... | |
int | getVariableIndex (const std::string &variable) const |
Get the index of a variable in the robot state. More... | |
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() More... | |
void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, double *values) const |
Compute the random values for a RobotState. More... | |
void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, std::map< std::string, double > &values) const |
Compute the random values for a RobotState. More... | |
void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values) const |
Compute the random values for a RobotState. More... | |
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) More... | |
void | printModelInfo (std::ostream &out) const |
Print information about the constructed model. More... | |
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. More... | |
bool | satisfiesPositionBounds (const double *state, const JointBoundsVector &active_joint_bounds, double margin=0.0) const |
bool | satisfiesPositionBounds (const double *state, 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) More... | |
~RobotModel () | |
Destructor. Clear all memory. More... | |
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. More... | |
const std::string & | getRootJointName () const |
Return the name of the root joint. Throws an exception if there is no root joint. More... | |
bool | hasJointModel (const std::string &name) const |
Check if a joint exists. Return true if it does. More... | |
const JointModel * | getJointModel (const std::string &joint) const |
Get a joint by its name. Output error and return NULL when the joint is missing. More... | |
const JointModel * | getJointModel (int index) const |
Get a joint by its index. Output error and return NULL when the link is missing. More... | |
JointModel * | getJointModel (const std::string &joint) |
Get a joint by its name. Output error and return NULL when the joint is missing. More... | |
const std::vector< const JointModel * > & | getJointModels () const |
Get the array of joints, in the order they appear in the robot state. More... | |
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(). More... | |
const std::vector< std::string > & | getJointModelNames () const |
Get the array of joint names, in the order they appear in the robot state. More... | |
const std::vector< const JointModel * > & | getActiveJointModels () const |
Get the array of joints that are active (not fixed, not mimic) in this model. More... | |
const std::vector< std::string > & | getActiveJointModelNames () const |
Get the array of active joint names, in the order they appear in the robot state. More... | |
const std::vector< JointModel * > & | getActiveJointModels () |
Get the array of joints that are active (not fixed, not mimic) in this model. More... | |
const std::vector< const JointModel * > & | getSingleDOFJointModels () const |
This is a list of all single-dof joints (including mimic joints) More... | |
const std::vector< const JointModel * > & | getMultiDOFJointModels () const |
This is a list of all multi-dof joints. More... | |
const std::vector< const JointModel * > & | getContinuousJointModels () const |
Get the array of continuous joints, in the order they appear in the robot state. More... | |
const std::vector< const JointModel * > & | getMimicJointModels () const |
Get the array of mimic joints, in the order they appear in the robot state. More... | |
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. More... | |
const JointModelGroup * | getJointModelGroup (const std::string &name) const |
Get a joint group from this model (by name) More... | |
JointModelGroup * | getJointModelGroup (const std::string &name) |
Get a joint group from this model (by name) More... | |
const std::vector< const JointModelGroup * > & | getJointModelGroups () const |
Get the available joint groups. More... | |
const std::vector< JointModelGroup * > & | getJointModelGroups () |
Get the available joint groups. More... | |
const std::vector< std::string > & | getJointModelGroupNames () const |
Get the names of all groups that are defined for this model. More... | |
bool | hasEndEffector (const std::string &eef) const |
Check if an end effector exists. More... | |
const JointModelGroup * | getEndEffector (const std::string &name) const |
Get the joint group that corresponds to a given end-effector name. More... | |
JointModelGroup * | getEndEffector (const std::string &name) |
Get the joint group that corresponds to a given end-effector name. More... | |
const std::vector< const JointModelGroup * > & | getEndEffectors () const |
Get the map between end effector names and the groups they correspond to. More... | |
Protected Member Functions | |
bool | addJointModelGroup (const srdf::Model::Group &group) |
Construct a JointModelGroup given a SRDF description group. More... | |
void | buildGroups (const srdf::Model &srdf_model) |
Given a SRDF model describing the groups, build up the groups in this kinematic model. More... | |
void | buildGroupsInfoEndEffectors (const srdf::Model &srdf_model) |
Compute helpful information about groups (that can be queried later) More... | |
void | buildGroupsInfoSubgroups () |
Compute helpful information about groups (that can be queried later) More... | |
void | buildGroupStates (const srdf::Model &srdf_model) |
Given a SRDF model describing the groups, build the default states defined in the SRDF. More... | |
void | buildJointInfo () |
Compute helpful information about joints. More... | |
void | buildMimic (const urdf::ModelInterface &urdf_model) |
Given the URDF model, build up the mimic joints (mutually constrained joints) More... | |
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. More... | |
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 More... | |
const JointModel * | computeCommonRoot (const JointModel *a, const JointModel *b) const |
Given two joints, find their common root. More... | |
void | computeCommonRoots () |
For every pair of joints, pre-compute the common roots of the joints. More... | |
void | computeDescendants () |
For every joint, pre-compute the list of descendant joints & links. More... | |
void | computeFixedTransforms (const LinkModel *link, const Eigen::Isometry3d &transform, LinkTransformMap &associated_transforms) |
Get the transforms between link and all its rigidly attached descendants. More... | |
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. More... | |
LinkModel * | constructLinkModel (const urdf::Link *urdf_link) |
Given a urdf link, build the corresponding LinkModel object. More... | |
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. More... | |
void | updateMimicJoints (double *values) const |
Update the variable values for the state of a group with respect to the mimic joints. More... | |
Protected Attributes | |
std::vector< std::string > | active_joint_model_names_vector_ |
The vector of joint names that corresponds to active_joint_model_vector_. More... | |
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. More... | |
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. More... | |
JointBoundsVector | active_joint_models_bounds_ |
The bounds for all the active joint models. More... | |
std::vector< int > | common_joint_roots_ |
For every two joints, the index of the common root for thw joints is stored. More... | |
std::vector< const JointModel * > | continuous_joint_model_vector_ |
The set of continuous joints this model contains. More... | |
std::vector< const JointModelGroup * > | end_effectors_ |
The array of end-effectors, in alphabetical order. More... | |
JointModelGroupMap | end_effectors_map_ |
The known end effectors. More... | |
JointModelGroupMap | joint_model_group_map_ |
A map from group names to joint groups. More... | |
std::vector< std::string > | joint_model_group_names_ |
A vector of all group names, in alphabetical order. More... | |
std::vector< JointModelGroup * > | joint_model_groups_ |
The array of joint model groups, in alphabetical order. More... | |
std::vector< const JointModelGroup * > | joint_model_groups_const_ |
The array of joint model groups, in alphabetical order. More... | |
JointModelMap | joint_model_map_ |
A map from joint names to their instances. More... | |
std::vector< std::string > | joint_model_names_vector_ |
The vector of joint names that corresponds to joint_model_vector_. More... | |
std::vector< JointModel * > | joint_model_vector_ |
The vector of joints in the model, in the order they appear in the state vector. More... | |
std::vector< const JointModel * > | joint_model_vector_const_ |
The vector of joints in the model, in the order they appear in the state vector. More... | |
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. More... | |
std::vector< const JointModel * > | joints_of_variable_ |
The joints that correspond to each variable index. More... | |
std::size_t | link_geometry_count_ |
Total number of geometric shapes in this model. More... | |
LinkModelMap | link_model_map_ |
A map from link names to their instances. More... | |
std::vector< std::string > | link_model_names_vector_ |
The vector of link names that corresponds to link_model_vector_. More... | |
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_. More... | |
std::vector< LinkModel * > | link_model_vector_ |
The vector of links that are updated when computeTransforms() is called, in the order they are updated. More... | |
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. More... | |
std::vector< const LinkModel * > | link_models_with_collision_geometry_vector_ |
Only links that have collision geometry specified. More... | |
std::vector< const JointModel * > | mimic_joints_ |
The set of mimic joints this model contains. More... | |
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. More... | |
std::string | model_name_ |
The name of the robot. More... | |
std::vector< const JointModel * > | multi_dof_joints_ |
const JointModel * | root_joint_ |
The root joint. More... | |
const LinkModel * | root_link_ |
The first physical link for the robot. More... | |
std::vector< const JointModel * > | single_dof_joints_ |
srdf::ModelConstSharedPtr | srdf_ |
urdf::ModelInterfaceSharedPtr | urdf_ |
std::size_t | variable_count_ |
Get the number of variables necessary to describe this model. More... | |
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!) More... | |
Access to link models | |
const LinkModel * | getRootLink () const |
Get the physical root link of the robot. More... | |
const std::string & | getRootLinkName () const |
Get the name of the root link of the robot. More... | |
bool | hasLinkModel (const std::string &name) const |
Check if a link exists. Return true if it does. More... | |
const LinkModel * | getLinkModel (const std::string &link, bool *has_link=nullptr) const |
Get a link by its name. Output error and return NULL when the link is missing. More... | |
const LinkModel * | getLinkModel (int index) const |
Get a link by its index. Output error and return NULL when the link is missing. More... | |
LinkModel * | getLinkModel (const std::string &link, bool *has_link=nullptr) |
Get a link by its name. Output error and return NULL when the link is missing. More... | |
const std::vector< const LinkModel * > & | getLinkModels () const |
Get the array of links More... | |
const std::vector< LinkModel * > & | getLinkModels () |
Get the array of links More... | |
const std::vector< std::string > & | getLinkModelNames () const |
Get the link names (of all links) More... | |
const std::vector< const LinkModel * > & | getLinkModelsWithCollisionGeometry () const |
Get the link models that have some collision geometry associated to themselves. More... | |
const std::vector< std::string > & | getLinkModelNamesWithCollisionGeometry () const |
Get the names of the link models that have some collision geometry associated to themselves. More... | |
std::size_t | getLinkModelCount () const |
std::size_t | getLinkGeometryCount () const |
static const moveit::core::LinkModel * | getRigidlyConnectedParentLinkModel (const LinkModel *link, Eigen::Isometry3d &transform, const JointModelGroup *jmg=nullptr) |
Get the latest link upwards the kinematic tree, which is only connected via fixed joints. More... | |
static const moveit::core::LinkModel * | getRigidlyConnectedParentLinkModel (const LinkModel *link, const JointModelGroup *jmg=nullptr) |
Definition of a kinematic model. This class is not thread safe, however multiple instances can be created.
Definition at line 143 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 123 of file robot_model.cpp.
moveit::core::RobotModel::~RobotModel | ( | ) |
Destructor. Clear all memory.
Definition at line 131 of file robot_model.cpp.
|
protected |
Construct a JointModelGroup given a SRDF description group.
Definition at line 733 of file robot_model.cpp.
|
protected |
Given a SRDF model describing the groups, build up the groups in this kinematic model.
Definition at line 569 of file robot_model.cpp.
|
protected |
Compute helpful information about groups (that can be queried later)
Definition at line 650 of file robot_model.cpp.
|
protected |
Compute helpful information about groups (that can be queried later)
Definition at line 621 of file robot_model.cpp.
|
protected |
Given a SRDF model describing the groups, build the default states defined in the SRDF.
Definition at line 390 of file robot_model.cpp.
|
protected |
Compute helpful information about joints.
Definition at line 315 of file robot_model.cpp.
|
protected |
Given the URDF model, build up the mimic joints (mutually constrained joints)
Definition at line 450 of file robot_model.cpp.
|
protected |
Given an URDF model and a SRDF model, build a full kinematic model.
Definition at line 151 of file robot_model.cpp.
|
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 849 of file robot_model.cpp.
|
protected |
Given two joints, find their common root.
|
protected |
For every pair of joints, pre-compute the common roots of the joints.
Definition at line 264 of file robot_model.cpp.
|
protected |
For every joint, pre-compute the list of descendant joints & links.
Definition at line 295 of file robot_model.cpp.
|
protected |
Get the transforms between link and all its rigidly attached descendants.
Definition at line 1619 of file robot_model.cpp.
|
protected |
Given a urdf joint model, a child link and a set of virtual joints, build up the corresponding JointModel object.
Definition at line 946 of file robot_model.cpp.
|
protected |
Given a urdf link, build the corresponding LinkModel object.
Definition at line 1161 of file robot_model.cpp.
|
protected |
Given a geometry spec from the URDF and a filename (for a mesh), construct the corresponding shape object.
Definition at line 1237 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. Only considers active joints.
Definition at line 1476 of file robot_model.cpp.
|
inline |
Definition at line 418 of file robot_model.h.
bool moveit::core::RobotModel::enforcePositionBounds | ( | double * | state, |
const JointBoundsVector & | active_joint_bounds | ||
) | const |
Definition at line 1463 of file robot_model.cpp.
|
inline |
Get the array of active joint names, in the order they appear in the robot state.
Definition at line 244 of file robot_model.h.
|
inline |
Get the array of joints that are active (not fixed, not mimic) in this model.
Definition at line 250 of file robot_model.h.
|
inline |
Get the array of joints that are active (not fixed, not mimic) in this model.
Definition at line 238 of file robot_model.h.
|
inline |
Get the bounds for all the active joints.
Definition at line 518 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 530 of file robot_model.h.
|
inline |
Get the array of continuous joints, in the order they appear in the robot state.
Definition at line 269 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 528 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 514 of file robot_model.cpp.
|
inline |
Get the map between end effector names and the groups they correspond to.
Definition at line 489 of file robot_model.h.
JointModel * moveit::core::RobotModel::getJointModel | ( | const std::string & | joint | ) |
Get a joint by its name. Output error and return NULL when the joint is missing.
Definition at line 1306 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 NULL when the joint is missing.
Definition at line 1286 of file robot_model.cpp.
const JointModel * moveit::core::RobotModel::getJointModel | ( | int | index | ) | const |
Get a joint by its index. Output error and return NULL when the link is missing.
Definition at line 1295 of file robot_model.cpp.
|
inline |
Definition at line 291 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 558 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 547 of file robot_model.cpp.
|
inline |
Get the names of all groups that are defined for this model.
Definition at line 474 of file robot_model.h.
|
inline |
Get the available joint groups.
Definition at line 468 of file robot_model.h.
|
inline |
Get the available joint groups.
Definition at line 462 of file robot_model.h.
|
inline |
Get the array of joint names, in the order they appear in the robot state.
Definition at line 232 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 226 of file robot_model.h.
|
inline |
Get the array of joints, in the order they appear in the robot state.
Definition at line 218 of file robot_model.h.
|
inline |
Definition at line 286 of file robot_model.h.
|
inline |
Definition at line 281 of file robot_model.h.
|
inline |
Definition at line 384 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 NULL when the link is missing.
Definition at line 1331 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 NULL when the link is missing.
Definition at line 1315 of file robot_model.cpp.
const LinkModel * moveit::core::RobotModel::getLinkModel | ( | int | index | ) | const |
Get a link by its index. Output error and return NULL when the link is missing.
Definition at line 1320 of file robot_model.cpp.
|
inline |
Definition at line 379 of file robot_model.h.
|
inline |
Get the link names (of all links)
Definition at line 362 of file robot_model.h.
|
inline |
Get the names of the link models that have some collision geometry associated to themselves.
Definition at line 374 of file robot_model.h.
|
inline |
Get the array of links
Definition at line 356 of file robot_model.h.
|
inline |
Get the array of links
Definition at line 350 of file robot_model.h.
|
inline |
Get the link models that have some collision geometry associated to themselves.
Definition at line 368 of file robot_model.h.
|
inline |
Definition at line 429 of file robot_model.h.
double moveit::core::RobotModel::getMaximumExtent | ( | const JointBoundsVector & | active_joint_bounds | ) | const |
Definition at line 1443 of file robot_model.cpp.
|
inline |
Get the array of mimic joints, in the order they appear in the robot state.
Definition at line 276 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 1424 of file robot_model.cpp.
|
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 162 of file robot_model.h.
|
inline |
This is a list of all multi-dof joints.
Definition at line 262 of file robot_model.h.
|
inline |
Get the model name.
Definition at line 153 of file robot_model.h.
|
inlinestatic |
Definition at line 342 of file robot_model.h.
|
static |
Get the latest link upwards the kinematic tree, which is only connected via fixed joints.
If jmg is given, all links that are not active in this JMG are considered fixed. Otherwise only fixed joints are considered fixed.
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 1346 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 141 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 199 of file robot_model.h.
const LinkModel * moveit::core::RobotModel::getRootLink | ( | ) | const |
Get the physical root link of the robot.
Definition at line 146 of file robot_model.cpp.
|
inline |
Get the name of the root link of the robot.
Definition at line 306 of file robot_model.h.
|
inline |
This is a list of all single-dof joints (including mimic joints)
Definition at line 256 of file robot_model.h.
|
inline |
Get the parsed SRDF model.
Definition at line 180 of file robot_model.h.
|
inline |
Get the parsed URDF model.
Definition at line 174 of file robot_model.h.
|
inline |
Get the bounds for a specific variable. Throw an exception of variable is not found.
Definition at line 512 of file robot_model.h.
|
inline |
Get the number of variables that describe this model.
Definition at line 497 of file robot_model.h.
void moveit::core::RobotModel::getVariableDefaultPositions | ( | double * | values | ) | const |
Compute the default values for a RobotState.
Definition at line 1408 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 1415 of file robot_model.cpp.
|
inline |
Compute the default values for a RobotState.
Definition at line 405 of file robot_model.h.
int moveit::core::RobotModel::getVariableIndex | ( | const std::string & | variable | ) | const |
Get the index of a variable in the robot state.
Definition at line 1435 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 506 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 1391 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 1398 of file robot_model.cpp.
|
inline |
Compute the random values for a RobotState.
Definition at line 398 of file robot_model.h.
bool moveit::core::RobotModel::hasEndEffector | ( | const std::string & | eef | ) | const |
Check if an end effector exists.
Definition at line 509 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 1276 of file robot_model.cpp.
bool moveit::core::RobotModel::hasJointModelGroup | ( | const std::string & | group | ) | const |
Check if the JointModelGroup group exists.
Definition at line 542 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 1281 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 1486 of file robot_model.cpp.
|
inline |
Return true if the model is empty (has no root link, no joints)
Definition at line 168 of file robot_model.h.
void moveit::core::RobotModel::printModelInfo | ( | std::ostream & | out | ) | const |
Print information about the constructed model.
Definition at line 1570 of file robot_model.cpp.
bool moveit::core::RobotModel::satisfiesPositionBounds | ( | const double * | state, |
const JointBoundsVector & | active_joint_bounds, | ||
double | margin = 0.0 |
||
) | const |
Definition at line 1452 of file robot_model.cpp.
|
inline |
Definition at line 423 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 1498 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 1381 of file robot_model.cpp.
|
protected |
The vector of joint names that corresponds to active_joint_model_vector_.
Definition at line 613 of file robot_model.h.
|
protected |
Definition at line 651 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 610 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 616 of file robot_model.h.
|
protected |
The bounds for all the active joint models.
Definition at line 654 of file robot_model.h.
|
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 635 of file robot_model.h.
|
protected |
The set of continuous joints this model contains.
Definition at line 619 of file robot_model.h.
|
protected |
The array of end-effectors, in alphabetical order.
Definition at line 677 of file robot_model.h.
|
protected |
The known end effectors.
Definition at line 665 of file robot_model.h.
|
protected |
A map from group names to joint groups.
Definition at line 662 of file robot_model.h.
|
protected |
A vector of all group names, in alphabetical order.
Definition at line 674 of file robot_model.h.
|
protected |
The array of joint model groups, in alphabetical order.
Definition at line 668 of file robot_model.h.
|
protected |
The array of joint model groups, in alphabetical order.
Definition at line 671 of file robot_model.h.
|
protected |
A map from joint names to their instances.
Definition at line 598 of file robot_model.h.
|
protected |
The vector of joint names that corresponds to joint_model_vector_.
Definition at line 607 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 601 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 604 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. Additionaly, it includes the names of the joints and the index for the first variable of that joint.
Definition at line 649 of file robot_model.h.
|
protected |
The joints that correspond to each variable index.
Definition at line 657 of file robot_model.h.
|
protected |
Total number of geometric shapes in this model.
Definition at line 590 of file robot_model.h.
|
protected |
A map from link names to their instances.
Definition at line 572 of file robot_model.h.
|
protected |
The vector of link names that corresponds to link_model_vector_.
Definition at line 581 of file robot_model.h.
|
protected |
The vector of link names that corresponds to link_models_with_collision_geometry_vector_.
Definition at line 587 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 575 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 578 of file robot_model.h.
|
protected |
Only links that have collision geometry specified.
Definition at line 584 of file robot_model.h.
|
protected |
The set of mimic joints this model contains.
Definition at line 622 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 560 of file robot_model.h.
|
protected |
The name of the robot.
Definition at line 556 of file robot_model.h.
|
protected |
Definition at line 626 of file robot_model.h.
|
protected |
The root joint.
Definition at line 595 of file robot_model.h.
|
protected |
The first physical link for the robot.
Definition at line 569 of file robot_model.h.
|
protected |
Definition at line 624 of file robot_model.h.
|
protected |
Definition at line 562 of file robot_model.h.
|
protected |
Definition at line 564 of file robot_model.h.
|
protected |
Get the number of variables necessary to describe this model.
Definition at line 644 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 641 of file robot_model.h.