#include <joint_model_group.h>
Public Member Functions | |
bool | canSetStateFromIK (const std::string &tip) const |
const std::vector< std::string > & | getAttachedEndEffectorNames () const |
Get the names of the end effectors attached to this group. | |
const std::vector< const JointModel * > & | getContinuousJointModels () const |
Get the array of continuous joints used in thir group. | |
unsigned int | getDefaultIKAttempts () const |
Get the default IK attempts. | |
double | getDefaultIKTimeout () const |
Get the default IK timeout. | |
const std::string & | getEndEffectorName () const |
Return the name of the end effector, if this group is an end-effector. | |
const std::pair< std::string, std::string > & | getEndEffectorParentGroup () const |
Get the name of the group this end-effector attaches to (first) and the name of the link in that group (second) | |
const std::vector< const JointModel * > & | getFixedJointModels () const |
Get the fixed joints that are part of this group. | |
const JointModel * | getJointModel (const std::string &joint) const |
Get a joint by its name. Return NULL if the joint is not part of this group. | |
const std::vector< std::string > & | getJointModelNames () const |
Get the names of the active joints in this group. These are the names of the joints returned by getJointModels(). | |
const std::vector< const JointModel * > & | getJointModels () const |
Get the active joints in this group (that have controllable DOF). This may not be the complete set of joints (see getFixedJointModels() and getMimicJointModels() ) | |
const std::vector< const JointModel * > & | getJointRoots () const |
Unlike a complete kinematic model, a group may contain disconnected parts of the kinematic tree -- a set of smaller trees. This function gives the roots of those smaller trees. Furthermore, it is ensured that the roots are on different branches in the kinematic tree. This means that in following any root in the given list, none of the other returned roots will be encountered. | |
const std::map< std::string, unsigned int > & | getJointVariablesIndexMap () const |
A joint group consists of an array of joints. Each joint has a specific ordering of its variables. Given the ordering of joints the group maintains, an ordering of all the variables of the group can be then constructed. The map from variable names to their position in the joint group state is given by this function. | |
const std::vector< unsigned int > & | getKinematicsSolverJointBijection () const |
Return the mapping between the order of the joints in this group and the order of the joints in the kinematics solver. | |
void | getKnownDefaultStates (std::vector< std::string > &default_states) const |
get the names of the known default states (as specified in the SRDF) | |
const LinkModel * | getLinkModel (const std::string &joint) const |
Get a joint by its name. Return NULL if the joint is not part of this group. | |
const std::vector< std::string > & | getLinkModelNames () const |
Get the names of the links that are part of this joint group. | |
const std::vector< std::string > & | getLinkModelNamesWithCollisionGeometry () const |
Get the names of the links that are part of this joint group and also have geometry associated with them. | |
const std::vector< const LinkModel * > & | getLinkModels () const |
Get the links that are part of this joint group. | |
double | getMaximumExtent (void) const |
Get the extent of the state space (the maximum value distance() can ever report for this group) | |
const std::vector< const JointModel * > & | getMimicJointModels () const |
Get the mimic joints that are part of this group. | |
const std::string & | getName () const |
Get the name of the joint group. | |
const RobotModel * | getParentModel () const |
Get the kinematic model this group is part of. | |
const std::pair < SolverAllocatorFn, SolverAllocatorMapFn > & | getSolverAllocators () const |
const kinematics::KinematicsBaseConstPtr & | getSolverInstance () const |
const kinematics::KinematicsBasePtr & | getSolverInstance () |
const std::vector< std::string > & | getSubgroupNames () const |
Get the names of the groups that are subsets of this one (in terms of joints set) | |
const std::vector< std::string > & | getUpdatedLinkModelNames () const |
Get the names of the links returned by getUpdatedLinkModels() | |
const std::vector< const LinkModel * > & | getUpdatedLinkModels () const |
Get the names of the links that are to be updated when the state of this group changes. This includes links that are in the kinematic model but outside this group, if those links are descendants of joints in this group that have their values updated. The order is the correct order for updating the corresponding states. | |
const std::vector< const LinkModel * > & | getUpdatedLinkModelsWithGeometry () const |
Get the names of the links that are to be updated when the state of this group changes. This includes links that are in the kinematic model but outside this group, if those links are descendants of joints in this group that have their values updated. | |
const std::vector< std::string > & | getUpdatedLinkModelsWithGeometryNames () const |
Get the names of the links returned by getUpdatedLinkModels() | |
const std::set< std::string > & | getUpdatedLinkModelsWithGeometryNamesSet () const |
Get the names of the links returned by getUpdatedLinkModels() | |
const std::set< const LinkModel * > & | getUpdatedLinkModelsWithGeometrySet () const |
Return the same data as getUpdatedLinkModelsWithGeometry() but as a set. | |
unsigned int | getVariableCount () const |
Get the number of variables that describe this joint group. | |
std::vector < moveit_msgs::JointLimits > | getVariableDefaultLimits () const |
Get the joint limits as read from the URDF. | |
bool | getVariableDefaultValues (const std::string &name, std::map< std::string, double > &values) const |
Get the values that correspond to a named state as read from the URDF. Return false on failure. | |
void | getVariableDefaultValues (std::vector< double > &values) const |
Compute the default values for the joint group. | |
void | getVariableDefaultValues (std::map< std::string, double > &values) const |
Compute the default values for the joint group. | |
std::vector < moveit_msgs::JointLimits > | getVariableLimits () const |
Get the joint limits specified by the user with setJointLimits() or the default joint limits using getVariableDefaultLimits(), if no joint limits were specified. | |
const std::vector< std::string > & | getVariableNames () const |
Get the names of the variables that make up the joints included in this group. 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 random values for the state of the joint group. | |
void | getVariableRandomValuesNearBy (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const std::vector< double > &near, const std::map< robot_model::JointModel::JointType, double > &distance_map) const |
Compute random values for the state of the joint group. | |
void | getVariableRandomValuesNearBy (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const std::vector< double > &near, const std::vector< double > &distances) const |
Compute random values for the state of the joint group. | |
bool | hasJointModel (const std::string &joint) const |
Check if a joint is part of this group. | |
bool | hasLinkModel (const std::string &link) const |
Check if a link is part of this group. | |
bool | isActiveDOF (const std::string &name) const |
Is the joint in the list of active joints in this group (that have controllable DOF). This may not be the complete set of joints (see getFixedJointModels() and getMimicJointModels() ) | |
bool | isChain () const |
Check if this group is a linear chain. | |
bool | isEndEffector () const |
Check if this group was designated as an end-effector in the SRDF. | |
bool | isLinkUpdated (const std::string &name) const |
True if this name is in the set of links that are to be updated when the state of this group changes. This includes links that are in the kinematic model but outside this group, if those links are descendants of joints in this group that have their values updated. | |
bool | isSubgroup (const std::string &group) const |
Check if the joints of group group are a subset of the joints in this group. | |
JointModelGroup (const std::string &name, const std::vector< const JointModel * > &joint_vector, const RobotModel *parent_model) | |
void | printGroupInfo (std::ostream &out=std::cout) const |
Print information about the constructed model. | |
void | setDefaultIKAttempts (unsigned int ik_attempts) |
Set the default IK attempts. | |
void | setDefaultIKTimeout (double ik_timeout) |
Set the default IK timeout. | |
bool | setRedundantJoints (const std::vector< unsigned int > &joints) |
void | setSolverAllocators (const SolverAllocatorFn &solver, const SolverAllocatorMapFn &solver_map=SolverAllocatorMapFn()) |
void | setSolverAllocators (const std::pair< SolverAllocatorFn, SolverAllocatorMapFn > &solvers) |
void | setVariableLimits (const std::vector< moveit_msgs::JointLimits > &jlim) |
Override joint limits. | |
~JointModelGroup () | |
Protected Attributes | |
std::vector< std::string > | active_variable_names_ |
The names of the DOF that make up this group (this is just a sequence of joint variable names; not necessarily joint names!) | |
std::set< std::string > | active_variable_names_set_ |
The names of the DOF that make up this group (this is just a sequence of joint variable names; not necessarily joint names!) | |
std::vector< std::string > | attached_end_effector_names_ |
If an end-effector is attached to this group, the name of that end-effector is stored in this variable. | |
std::vector< const JointModel * > | continuous_joint_model_vector_const_ |
The set of continuous joints this group contains. | |
unsigned int | default_ik_attempts_ |
double | default_ik_timeout_ |
std::map< std::string, std::map< std::string, double > > | default_states_ |
The set of default states specified for this group in the SRDF. | |
std::string | end_effector_name_ |
The name of the end effector, if this group is an end-effector. | |
std::pair< std::string, std::string > | end_effector_parent_ |
First: name of the group that is parent to this end-effector group; Second: the link this in the parent group that this group attaches to. | |
std::vector< const JointModel * > | fixed_joints_ |
The joints that have no DOF (fixed) | |
std::vector< unsigned int > | ik_joint_bijection_ |
bool | is_chain_ |
bool | is_end_effector_ |
Flag indicating whether this group is an end effector. | |
std::map< std::string, const JointModel * > | joint_model_map_ |
A map from joint names to their instances. | |
std::vector< std::string > | joint_model_name_vector_ |
Names of joints in the order they appear in the group state. | |
std::vector< const JointModel * > | joint_model_vector_ |
Joint instances in the order they appear in the group state. | |
std::vector< const JointModel * > | joint_roots_ |
The list of joint models that are roots in this group. | |
std::map< std::string, unsigned int > | joint_variables_index_map_ |
The group includes all the joint variables that make up the joints the group 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< std::string > | link_model_name_vector_ |
The names of the links in this group. | |
std::vector< const LinkModel * > | link_model_vector_ |
The links that are on the direct lineage between joints and joint_roots_, as well as the children of the joint leafs. May not be in any particular order. | |
std::vector< std::string > | link_model_with_geometry_name_vector_ |
The names of the links in this group that also have geometry. | |
std::vector< const JointModel * > | mimic_joints_ |
Joints that mimic other joints. | |
std::string | name_ |
Name of group. | |
const RobotModel * | parent_model_ |
Owner model. | |
std::pair< SolverAllocatorFn, SolverAllocatorMapFn > | solver_allocators_ |
kinematics::KinematicsBasePtr | solver_instance_ |
kinematics::KinematicsBaseConstPtr | solver_instance_const_ |
std::vector< std::string > | subgroup_names_ |
The set of labelled subgroups that are included in this group. | |
std::set< std::string > | updated_link_model_name_set_ |
The list of downstream link names in the order they should be updated (may include links that are not in this group) | |
std::vector< std::string > | updated_link_model_name_vector_ |
The list of downstream link names in the order they should be updated (may include links that are not in this group) | |
std::set< const LinkModel * > | updated_link_model_set_ |
The list of downstream link models in the order they should be updated (may include links that are not in this group) | |
std::vector< const LinkModel * > | updated_link_model_vector_ |
The list of downstream link models in the order they should be updated (may include links that are not in this group) | |
std::set< std::string > | updated_link_model_with_geometry_name_set_ |
The list of downstream link names in the order they should be updated (may include links that are not in this group) | |
std::vector< std::string > | updated_link_model_with_geometry_name_vector_ |
The list of downstream link names in the order they should be updated (may include links that are not in this group) | |
std::set< const LinkModel * > | updated_link_model_with_geometry_set_ |
The list of downstream link models in the order they should be updated (may include links that are not in this group) | |
std::vector< const LinkModel * > | updated_link_model_with_geometry_vector_ |
The list of downstream link models in the order they should be updated (may include links that are not in this group) | |
unsigned int | variable_count_ |
The number of variables necessary to describe this group of joints. | |
Friends | |
class | RobotModel |
Definition at line 58 of file joint_model_group.h.
robot_model::JointModelGroup::JointModelGroup | ( | const std::string & | name, |
const std::vector< const JointModel * > & | joint_vector, | ||
const RobotModel * | parent_model | ||
) |
Definition at line 87 of file joint_model_group.cpp.
Definition at line 214 of file joint_model_group.cpp.
bool robot_model::JointModelGroup::canSetStateFromIK | ( | const std::string & | tip | ) | const |
Definition at line 397 of file joint_model_group.cpp.
const std::vector<std::string>& robot_model::JointModelGroup::getAttachedEndEffectorNames | ( | ) | const [inline] |
Get the names of the end effectors attached to this group.
Definition at line 285 of file joint_model_group.h.
const std::vector<const JointModel*>& robot_model::JointModelGroup::getContinuousJointModels | ( | ) | const [inline] |
Get the array of continuous joints used in thir group.
Definition at line 118 of file joint_model_group.h.
unsigned int robot_model::JointModelGroup::getDefaultIKAttempts | ( | ) | const [inline] |
Get the default IK attempts.
Definition at line 343 of file joint_model_group.h.
double robot_model::JointModelGroup::getDefaultIKTimeout | ( | ) | const [inline] |
Get the default IK timeout.
Definition at line 334 of file joint_model_group.h.
const std::string& robot_model::JointModelGroup::getEndEffectorName | ( | ) | const [inline] |
Return the name of the end effector, if this group is an end-effector.
Definition at line 273 of file joint_model_group.h.
const std::pair<std::string, std::string>& robot_model::JointModelGroup::getEndEffectorParentGroup | ( | ) | const [inline] |
Get the name of the group this end-effector attaches to (first) and the name of the link in that group (second)
Definition at line 279 of file joint_model_group.h.
const std::vector<const JointModel*>& robot_model::JointModelGroup::getFixedJointModels | ( | ) | const [inline] |
Get the fixed joints that are part of this group.
Definition at line 106 of file joint_model_group.h.
const robot_model::JointModel * robot_model::JointModelGroup::getJointModel | ( | const std::string & | joint | ) | const |
Get a joint by its name. Return NULL if the joint is not part of this group.
Definition at line 236 of file joint_model_group.cpp.
const std::vector<std::string>& robot_model::JointModelGroup::getJointModelNames | ( | ) | const [inline] |
Get the names of the active joints in this group. These are the names of the joints returned by getJointModels().
Definition at line 100 of file joint_model_group.h.
const std::vector<const JointModel*>& robot_model::JointModelGroup::getJointModels | ( | ) | const [inline] |
Get the active joints in this group (that have controllable DOF). This may not be the complete set of joints (see getFixedJointModels() and getMimicJointModels() )
Definition at line 94 of file joint_model_group.h.
const std::vector<const JointModel*>& robot_model::JointModelGroup::getJointRoots | ( | ) | const [inline] |
Unlike a complete kinematic model, a group may contain disconnected parts of the kinematic tree -- a set of smaller trees. This function gives the roots of those smaller trees. Furthermore, it is ensured that the roots are on different branches in the kinematic tree. This means that in following any root in the given list, none of the other returned roots will be encountered.
Definition at line 138 of file joint_model_group.h.
const std::map<std::string, unsigned int>& robot_model::JointModelGroup::getJointVariablesIndexMap | ( | ) | const [inline] |
A joint group consists of an array of joints. Each joint has a specific ordering of its variables. Given the ordering of joints the group maintains, an ordering of all the variables of the group can be then constructed. The map from variable names to their position in the joint group state is given by this function.
Definition at line 219 of file joint_model_group.h.
const std::vector<unsigned int>& robot_model::JointModelGroup::getKinematicsSolverJointBijection | ( | ) | const [inline] |
Return the mapping between the order of the joints in this group and the order of the joints in the kinematics solver.
Definition at line 355 of file joint_model_group.h.
void robot_model::JointModelGroup::getKnownDefaultStates | ( | std::vector< std::string > & | default_states | ) | const |
get the names of the known default states (as specified in the SRDF)
Definition at line 302 of file joint_model_group.cpp.
const LinkModel* robot_model::JointModelGroup::getLinkModel | ( | const std::string & | joint | ) | const |
Get a joint by its name. Return NULL if the joint is not part of this group.
const std::vector<std::string>& robot_model::JointModelGroup::getLinkModelNames | ( | ) | const [inline] |
Get the names of the links that are part of this joint group.
Definition at line 150 of file joint_model_group.h.
const std::vector<std::string>& robot_model::JointModelGroup::getLinkModelNamesWithCollisionGeometry | ( | ) | const [inline] |
Get the names of the links that are part of this joint group and also have geometry associated with them.
Definition at line 156 of file joint_model_group.h.
const std::vector<const LinkModel*>& robot_model::JointModelGroup::getLinkModels | ( | ) | const [inline] |
Get the links that are part of this joint group.
Definition at line 144 of file joint_model_group.h.
double robot_model::JointModelGroup::getMaximumExtent | ( | void | ) | const |
Get the extent of the state space (the maximum value distance() can ever report for this group)
Definition at line 294 of file joint_model_group.cpp.
const std::vector<const JointModel*>& robot_model::JointModelGroup::getMimicJointModels | ( | ) | const [inline] |
Get the mimic joints that are part of this group.
Definition at line 112 of file joint_model_group.h.
const std::string& robot_model::JointModelGroup::getName | ( | ) | const [inline] |
Get the name of the joint group.
Definition at line 75 of file joint_model_group.h.
const RobotModel* robot_model::JointModelGroup::getParentModel | ( | ) | const [inline] |
Get the kinematic model this group is part of.
Definition at line 69 of file joint_model_group.h.
const std::pair<SolverAllocatorFn, SolverAllocatorMapFn>& robot_model::JointModelGroup::getSolverAllocators | ( | ) | const [inline] |
Definition at line 302 of file joint_model_group.h.
const kinematics::KinematicsBaseConstPtr& robot_model::JointModelGroup::getSolverInstance | ( | ) | const [inline] |
Definition at line 314 of file joint_model_group.h.
const kinematics::KinematicsBasePtr& robot_model::JointModelGroup::getSolverInstance | ( | ) | [inline] |
Definition at line 319 of file joint_model_group.h.
const std::vector<std::string>& robot_model::JointModelGroup::getSubgroupNames | ( | ) | const [inline] |
Get the names of the groups that are subsets of this one (in terms of joints set)
Definition at line 252 of file joint_model_group.h.
const std::vector<std::string>& robot_model::JointModelGroup::getUpdatedLinkModelNames | ( | ) | const [inline] |
Get the names of the links returned by getUpdatedLinkModels()
Definition at line 170 of file joint_model_group.h.
const std::vector<const LinkModel*>& robot_model::JointModelGroup::getUpdatedLinkModels | ( | ) | const [inline] |
Get the names of the links that are to be updated when the state of this group changes. This includes links that are in the kinematic model but outside this group, if those links are descendants of joints in this group that have their values updated. The order is the correct order for updating the corresponding states.
Definition at line 164 of file joint_model_group.h.
const std::vector<const LinkModel*>& robot_model::JointModelGroup::getUpdatedLinkModelsWithGeometry | ( | ) | const [inline] |
Get the names of the links that are to be updated when the state of this group changes. This includes links that are in the kinematic model but outside this group, if those links are descendants of joints in this group that have their values updated.
Definition at line 178 of file joint_model_group.h.
const std::vector<std::string>& robot_model::JointModelGroup::getUpdatedLinkModelsWithGeometryNames | ( | ) | const [inline] |
Get the names of the links returned by getUpdatedLinkModels()
Definition at line 190 of file joint_model_group.h.
const std::set<std::string>& robot_model::JointModelGroup::getUpdatedLinkModelsWithGeometryNamesSet | ( | ) | const [inline] |
Get the names of the links returned by getUpdatedLinkModels()
Definition at line 196 of file joint_model_group.h.
const std::set<const LinkModel*>& robot_model::JointModelGroup::getUpdatedLinkModelsWithGeometrySet | ( | ) | const [inline] |
Return the same data as getUpdatedLinkModelsWithGeometry() but as a set.
Definition at line 184 of file joint_model_group.h.
unsigned int robot_model::JointModelGroup::getVariableCount | ( | ) | const [inline] |
Get the number of variables that describe this joint group.
Definition at line 246 of file joint_model_group.h.
std::vector< moveit_msgs::JointLimits > robot_model::JointModelGroup::getVariableDefaultLimits | ( | ) | const |
Get the joint limits as read from the URDF.
Definition at line 332 of file joint_model_group.cpp.
bool robot_model::JointModelGroup::getVariableDefaultValues | ( | const std::string & | name, |
std::map< std::string, double > & | values | ||
) | const |
Get the values that correspond to a named state as read from the URDF. Return false on failure.
Definition at line 310 of file joint_model_group.cpp.
void robot_model::JointModelGroup::getVariableDefaultValues | ( | std::vector< double > & | values | ) | const |
Compute the default values for the joint group.
Definition at line 319 of file joint_model_group.cpp.
void robot_model::JointModelGroup::getVariableDefaultValues | ( | std::map< std::string, double > & | values | ) | const |
Compute the default values for the joint group.
Definition at line 326 of file joint_model_group.cpp.
std::vector< moveit_msgs::JointLimits > robot_model::JointModelGroup::getVariableLimits | ( | ) | const |
Get the joint limits specified by the user with setJointLimits() or the default joint limits using getVariableDefaultLimits(), if no joint limits were specified.
Definition at line 343 of file joint_model_group.cpp.
const std::vector<std::string>& robot_model::JointModelGroup::getVariableNames | ( | ) | const [inline] |
Get the names of the variables that make up the joints included in this group. 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 126 of file joint_model_group.h.
void robot_model::JointModelGroup::getVariableRandomValues | ( | random_numbers::RandomNumberGenerator & | rng, |
std::vector< double > & | values | ||
) | const |
Compute random values for the state of the joint group.
Definition at line 248 of file joint_model_group.cpp.
void robot_model::JointModelGroup::getVariableRandomValuesNearBy | ( | random_numbers::RandomNumberGenerator & | rng, |
std::vector< double > & | values, | ||
const std::vector< double > & | near, | ||
const std::map< robot_model::JointModel::JointType, double > & | distance_map | ||
) | const |
Compute random values for the state of the joint group.
Definition at line 254 of file joint_model_group.cpp.
void robot_model::JointModelGroup::getVariableRandomValuesNearBy | ( | random_numbers::RandomNumberGenerator & | rng, |
std::vector< double > & | values, | ||
const std::vector< double > & | near, | ||
const std::vector< double > & | distances | ||
) | const |
Compute random values for the state of the joint group.
Definition at line 275 of file joint_model_group.cpp.
bool robot_model::JointModelGroup::hasJointModel | ( | const std::string & | joint | ) | const |
Check if a joint is part of this group.
Definition at line 226 of file joint_model_group.cpp.
bool robot_model::JointModelGroup::hasLinkModel | ( | const std::string & | link | ) | const |
Check if a link is part of this group.
Definition at line 231 of file joint_model_group.cpp.
bool robot_model::JointModelGroup::isActiveDOF | ( | const std::string & | name | ) | const [inline] |
Is the joint in the list of active joints in this group (that have controllable DOF). This may not be the complete set of joints (see getFixedJointModels() and getMimicJointModels() )
Definition at line 211 of file joint_model_group.h.
bool robot_model::JointModelGroup::isChain | ( | ) | const [inline] |
Check if this group is a linear chain.
Definition at line 261 of file joint_model_group.h.
bool robot_model::JointModelGroup::isEndEffector | ( | ) | const [inline] |
Check if this group was designated as an end-effector in the SRDF.
Definition at line 267 of file joint_model_group.h.
bool robot_model::JointModelGroup::isLinkUpdated | ( | const std::string & | name | ) | const [inline] |
True if this name is in the set of links that are to be updated when the state of this group changes. This includes links that are in the kinematic model but outside this group, if those links are descendants of joints in this group that have their values updated.
Definition at line 204 of file joint_model_group.h.
bool robot_model::JointModelGroup::isSubgroup | ( | const std::string & | group | ) | const |
Check if the joints of group group are a subset of the joints in this group.
Definition at line 218 of file joint_model_group.cpp.
void robot_model::JointModelGroup::printGroupInfo | ( | std::ostream & | out = std::cout | ) | const |
Print information about the constructed model.
Definition at line 418 of file joint_model_group.cpp.
void robot_model::JointModelGroup::setDefaultIKAttempts | ( | unsigned int | ik_attempts | ) | [inline] |
Set the default IK attempts.
Definition at line 349 of file joint_model_group.h.
void robot_model::JointModelGroup::setDefaultIKTimeout | ( | double | ik_timeout | ) |
Set the default IK timeout.
Definition at line 362 of file joint_model_group.cpp.
bool robot_model::JointModelGroup::setRedundantJoints | ( | const std::vector< unsigned int > & | joints | ) | [inline] |
Definition at line 326 of file joint_model_group.h.
void robot_model::JointModelGroup::setSolverAllocators | ( | const SolverAllocatorFn & | solver, |
const SolverAllocatorMapFn & | solver_map = SolverAllocatorMapFn() |
||
) | [inline] |
Definition at line 307 of file joint_model_group.h.
void robot_model::JointModelGroup::setSolverAllocators | ( | const std::pair< SolverAllocatorFn, SolverAllocatorMapFn > & | solvers | ) |
Definition at line 369 of file joint_model_group.cpp.
void robot_model::JointModelGroup::setVariableLimits | ( | const std::vector< moveit_msgs::JointLimits > & | jlim | ) |
Override joint limits.
Definition at line 354 of file joint_model_group.cpp.
friend class RobotModel [friend] |
Definition at line 60 of file joint_model_group.h.
std::vector<std::string> robot_model::JointModelGroup::active_variable_names_ [protected] |
The names of the DOF that make up this group (this is just a sequence of joint variable names; not necessarily joint names!)
Definition at line 398 of file joint_model_group.h.
std::set<std::string> robot_model::JointModelGroup::active_variable_names_set_ [protected] |
The names of the DOF that make up this group (this is just a sequence of joint variable names; not necessarily joint names!)
Definition at line 401 of file joint_model_group.h.
std::vector<std::string> robot_model::JointModelGroup::attached_end_effector_names_ [protected] |
If an end-effector is attached to this group, the name of that end-effector is stored in this variable.
Definition at line 448 of file joint_model_group.h.
std::vector<const JointModel*> robot_model::JointModelGroup::continuous_joint_model_vector_const_ [protected] |
The set of continuous joints this group contains.
Definition at line 395 of file joint_model_group.h.
unsigned int robot_model::JointModelGroup::default_ik_attempts_ [protected] |
Definition at line 468 of file joint_model_group.h.
double robot_model::JointModelGroup::default_ik_timeout_ [protected] |
Definition at line 466 of file joint_model_group.h.
std::map<std::string, std::map<std::string, double> > robot_model::JointModelGroup::default_states_ [protected] |
The set of default states specified for this group in the SRDF.
Definition at line 471 of file joint_model_group.h.
std::string robot_model::JointModelGroup::end_effector_name_ [protected] |
The name of the end effector, if this group is an end-effector.
Definition at line 454 of file joint_model_group.h.
std::pair<std::string, std::string> robot_model::JointModelGroup::end_effector_parent_ [protected] |
First: name of the group that is parent to this end-effector group; Second: the link this in the parent group that this group attaches to.
Definition at line 451 of file joint_model_group.h.
std::vector<const JointModel*> robot_model::JointModelGroup::fixed_joints_ [protected] |
The joints that have no DOF (fixed)
Definition at line 389 of file joint_model_group.h.
std::vector<unsigned int> robot_model::JointModelGroup::ik_joint_bijection_ [protected] |
Definition at line 464 of file joint_model_group.h.
bool robot_model::JointModelGroup::is_chain_ [protected] |
Definition at line 456 of file joint_model_group.h.
bool robot_model::JointModelGroup::is_end_effector_ [protected] |
Flag indicating whether this group is an end effector.
Definition at line 445 of file joint_model_group.h.
std::map<std::string, const JointModel*> robot_model::JointModelGroup::joint_model_map_ [protected] |
A map from joint names to their instances.
Definition at line 378 of file joint_model_group.h.
std::vector<std::string> robot_model::JointModelGroup::joint_model_name_vector_ [protected] |
Names of joints in the order they appear in the group state.
Definition at line 372 of file joint_model_group.h.
std::vector<const JointModel*> robot_model::JointModelGroup::joint_model_vector_ [protected] |
Joint instances in the order they appear in the group state.
Definition at line 375 of file joint_model_group.h.
std::vector<const JointModel*> robot_model::JointModelGroup::joint_roots_ [protected] |
The list of joint models that are roots in this group.
Definition at line 381 of file joint_model_group.h.
std::map<std::string, unsigned int> robot_model::JointModelGroup::joint_variables_index_map_ [protected] |
The group includes all the joint variables that make up the joints the group 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 386 of file joint_model_group.h.
std::vector<std::string> robot_model::JointModelGroup::link_model_name_vector_ [protected] |
The names of the links in this group.
Definition at line 409 of file joint_model_group.h.
std::vector<const LinkModel*> robot_model::JointModelGroup::link_model_vector_ [protected] |
The links that are on the direct lineage between joints and joint_roots_, as well as the children of the joint leafs. May not be in any particular order.
Definition at line 406 of file joint_model_group.h.
std::vector<std::string> robot_model::JointModelGroup::link_model_with_geometry_name_vector_ [protected] |
The names of the links in this group that also have geometry.
Definition at line 412 of file joint_model_group.h.
std::vector<const JointModel*> robot_model::JointModelGroup::mimic_joints_ [protected] |
Joints that mimic other joints.
Definition at line 392 of file joint_model_group.h.
std::string robot_model::JointModelGroup::name_ [protected] |
Name of group.
Definition at line 369 of file joint_model_group.h.
const RobotModel* robot_model::JointModelGroup::parent_model_ [protected] |
Owner model.
Definition at line 366 of file joint_model_group.h.
std::pair<SolverAllocatorFn, SolverAllocatorMapFn> robot_model::JointModelGroup::solver_allocators_ [protected] |
Definition at line 458 of file joint_model_group.h.
Definition at line 462 of file joint_model_group.h.
Definition at line 460 of file joint_model_group.h.
std::vector<std::string> robot_model::JointModelGroup::subgroup_names_ [protected] |
The set of labelled subgroups that are included in this group.
Definition at line 442 of file joint_model_group.h.
std::set<std::string> robot_model::JointModelGroup::updated_link_model_name_set_ [protected] |
The list of downstream link names in the order they should be updated (may include links that are not in this group)
Definition at line 424 of file joint_model_group.h.
std::vector<std::string> robot_model::JointModelGroup::updated_link_model_name_vector_ [protected] |
The list of downstream link names in the order they should be updated (may include links that are not in this group)
Definition at line 421 of file joint_model_group.h.
std::set<const LinkModel*> robot_model::JointModelGroup::updated_link_model_set_ [protected] |
The list of downstream link models in the order they should be updated (may include links that are not in this group)
Definition at line 418 of file joint_model_group.h.
std::vector<const LinkModel*> robot_model::JointModelGroup::updated_link_model_vector_ [protected] |
The list of downstream link models in the order they should be updated (may include links that are not in this group)
Definition at line 415 of file joint_model_group.h.
std::set<std::string> robot_model::JointModelGroup::updated_link_model_with_geometry_name_set_ [protected] |
The list of downstream link names in the order they should be updated (may include links that are not in this group)
Definition at line 436 of file joint_model_group.h.
std::vector<std::string> robot_model::JointModelGroup::updated_link_model_with_geometry_name_vector_ [protected] |
The list of downstream link names in the order they should be updated (may include links that are not in this group)
Definition at line 433 of file joint_model_group.h.
std::set<const LinkModel*> robot_model::JointModelGroup::updated_link_model_with_geometry_set_ [protected] |
The list of downstream link models in the order they should be updated (may include links that are not in this group)
Definition at line 430 of file joint_model_group.h.
std::vector<const LinkModel*> robot_model::JointModelGroup::updated_link_model_with_geometry_vector_ [protected] |
The list of downstream link models in the order they should be updated (may include links that are not in this group)
Definition at line 427 of file joint_model_group.h.
unsigned int robot_model::JointModelGroup::variable_count_ [protected] |
The number of variables necessary to describe this group of joints.
Definition at line 439 of file joint_model_group.h.