moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <joint_model_group.h>
Classes | |
struct | GroupMimicUpdate |
struct | KinematicsSolver |
Public Types | |
using | KinematicsSolverMap = std::map< const JointModelGroup *, KinematicsSolver > |
Map from group instances to allocator functions & bijections. | |
Public Member Functions | |
JointModelGroup (const std::string &name, const srdf::Model::Group &config, const std::vector< const JointModel * > &joint_vector, const RobotModel *parent_model) | |
~JointModelGroup () | |
const RobotModel & | getParentModel () const |
Get the kinematic model this group is part of. | |
const std::string & | getName () const |
Get the name of the joint group. | |
const srdf::Model::Group & | getConfig () const |
get the SRDF configuration this group is based on | |
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. | |
const JointModel * | getJointModel (const std::string &joint) const |
Get a joint by its name. Throw an exception if the joint is not part of this group. | |
const LinkModel * | getLinkModel (const std::string &link) const |
Get a link by its name. Throw an exception if the link is not part of this group. | |
const std::vector< const JointModel * > & | getJointModels () const |
Get all the joints in this group (including fixed and mimic joints). | |
const std::vector< std::string > & | getJointModelNames () const |
Get the names of the joints in this group. These are the names of the joints returned by getJointModels(). | |
const std::vector< const JointModel * > & | getActiveJointModels () const |
Get the active joints in this group (that have controllable DOF). This does not include mimic joints. | |
const std::vector< std::string > & | getActiveJointModelNames () 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 * > & | getFixedJointModels () const |
Get the fixed joints that are part of this group. | |
const std::vector< const JointModel * > & | getMimicJointModels () const |
Get the mimic joints that are part of this group. | |
const std::vector< const JointModel * > & | getContinuousJointModels () const |
Get the array of continuous joints used in this group (may include mimic joints). | |
const std::vector< std::string > & | getVariableNames () const |
Get the names of the variables that make up the joints included in this group. The number of returned elements is always equal to getVariableCount(). This includes mimic joints. | |
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 JointModel * | getCommonRoot () const |
Get the common root of all joint roots; not necessarily part of this group. | |
const std::vector< const LinkModel * > & | getLinkModels () const |
Get the links that are part of this joint 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 * > & | 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::set< const LinkModel * > & | getUpdatedLinkModelsSet () const |
Return the same data as getUpdatedLinkModels() but as a set. | |
const std::vector< std::string > & | getUpdatedLinkModelNames () const |
Get the names of the links returned by getUpdatedLinkModels() | |
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::set< const LinkModel * > & | getUpdatedLinkModelsWithGeometrySet () const |
Return the same data as getUpdatedLinkModelsWithGeometry() but as a set. | |
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() | |
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. | |
const std::vector< int > & | getVariableIndexList () const |
Get the index locations in the complete robot state for all the variables in this group. | |
int | getVariableGroupIndex (const std::string &variable) const |
Get the index of a variable within the group. Return -1 on error. | |
const std::vector< std::string > & | getDefaultStateNames () const |
Get the names of the known default states (as specified in the SRDF) | |
void | addDefaultState (const std::string &name, const std::map< std::string, double > &default_state) |
bool | getVariableDefaultPositions (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 | getVariableDefaultPositions (std::map< std::string, double > &values) const |
Compute the default values for the joint group. | |
void | getVariableDefaultPositions (std::vector< double > &values) const |
Compute the default values for the joint group. | |
void | getVariableDefaultPositions (double *values) const |
Compute the default values for the joint group. | |
void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, double *values) const |
Compute random values for the state of the joint group. | |
void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values) const |
Compute random values for the state of the joint group. | |
void | getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const double *near, const double distance) const |
Compute random values for the state of the joint group. | |
void | getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const std::vector< double > &near, double distance) const |
Compute random values for the state of the joint group. | |
void | getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const std::vector< double > &near, const std::map< JointModel::JointType, double > &distance_map) const |
Compute random values for the state of the joint group. | |
void | getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const double *near, const std::vector< double > &distances) const |
Compute random values for the state of the joint group. | |
void | getVariableRandomPositionsNearBy (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. | |
void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, double *values, const JointBoundsVector &active_joint_bounds) const |
void | getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const JointBoundsVector &active_joint_bounds, const double *near, const double distance) const |
Compute random values for the state of the joint group. | |
void | getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const JointBoundsVector &active_joint_bounds, const double *near, const std::map< JointModel::JointType, double > &distance_map) const |
Compute random values for the state of the joint group. | |
void | getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const JointBoundsVector &active_joint_bounds, const double *near, const std::vector< double > &distances) const |
Compute random values for the state of the joint group. | |
bool | enforcePositionBounds (double *state) const |
bool | enforcePositionBounds (double *state, const JointBoundsVector &active_joint_bounds) const |
bool | satisfiesPositionBounds (const double *state, double margin=0.0) const |
bool | satisfiesPositionBounds (const double *state, const JointBoundsVector &active_joint_bounds, double margin=0.0) const |
double | getMaximumExtent () const |
double | getMaximumExtent (const JointBoundsVector &active_joint_bounds) const |
double | distance (const double *state1, const double *state2) const |
void | interpolate (const double *from, const double *to, double t, double *state) const |
unsigned int | getVariableCount () const |
Get the number of variables that describe this joint group. This includes variables necessary for mimic joints, so will always be >= getActiveVariableCount() | |
unsigned int | getActiveVariableCount () const |
Get the number of variables that describe the active joints in this joint group. This excludes variables necessary for mimic joints. | |
void | setSubgroupNames (const std::vector< std::string > &subgroups) |
Set the names of the subgroups for this group. | |
const std::vector< std::string > & | getSubgroupNames () const |
Get the names of the groups that are subsets of this one (in terms of joints set) | |
void | getSubgroups (std::vector< const JointModelGroup * > &sub_groups) const |
Get the groups that are subsets of this one (in terms of joints set) | |
bool | isSubgroup (const std::string &group) const |
Check if the joints of group group are a subset of the joints in this group. | |
bool | isChain () const |
Check if this group is a linear chain. | |
bool | isSingleDOFJoints () const |
Return true if the group consists only of joints that are single DOF. | |
bool | isEndEffector () const |
Check if this group was designated as an end-effector in the SRDF. | |
bool | isContiguousWithinState () const |
const std::string & | getEndEffectorName () const |
Return the name of the end effector, if this group is an end-effector. | |
void | setEndEffectorName (const std::string &name) |
Set the name of the end-effector, and remember this group is indeed an end-effector. | |
void | setEndEffectorParent (const std::string &group, const std::string &link) |
If this group is an end-effector, specify the parent group (e.g., the arm holding the eef) and the link the end effector connects to. | |
void | attachEndEffector (const std::string &eef_name) |
Notify this group that there is an end-effector attached to it. | |
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< std::string > & | getAttachedEndEffectorNames () const |
Get the names of the end effectors attached to this group. | |
bool | getEndEffectorTips (std::vector< const LinkModel * > &tips) const |
Get the unique set of end effector tips included in a particular joint model group as defined by the SRDF end effector elements e.g. for a humanoid robot this would return 4 tips for the hands and feet. | |
bool | getEndEffectorTips (std::vector< std::string > &tips) const |
Get the unique set of end effector tips included in a particular joint model group as defined by the SRDF end effector elements e.g. for a humanoid robot this would return 4 tips for the hands and feet. | |
const moveit::core::LinkModel * | getOnlyOneEndEffectorTip () const |
Get one end effector tip, throwing an error if there ends up being more in the joint model group This is a useful helper function because most planning groups (almost all) only have one tip. | |
const JointBoundsVector & | getActiveJointModelsBounds () const |
Get the bounds for all the active joints. | |
const std::pair< KinematicsSolver, KinematicsSolverMap > & | getGroupKinematics () const |
void | setSolverAllocators (const SolverAllocatorFn &solver, const SolverAllocatorMapFn &solver_map=SolverAllocatorMapFn()) |
void | setSolverAllocators (const std::pair< SolverAllocatorFn, SolverAllocatorMapFn > &solvers) |
const kinematics::KinematicsBaseConstPtr | getSolverInstance () const |
const kinematics::KinematicsBasePtr & | getSolverInstance () |
bool | canSetStateFromIK (const std::string &tip) const |
bool | setRedundantJoints (const std::vector< std::string > &joints) |
double | getDefaultIKTimeout () const |
Get the default IK timeout. | |
void | setDefaultIKTimeout (double ik_timeout) |
Set the default IK timeout. | |
const std::vector< size_t > & | getKinematicsSolverJointBijection () const |
Return the mapping between the order of the joints in this group and the order of the joints in the kinematics solver. An element bijection[i] at index i in this array, maps the variable at index bijection[i] in this group to the variable at index i in the kinematic solver. | |
void | printGroupInfo (std::ostream &out=std::cout) const |
Print information about the constructed model. | |
bool | isValidVelocityMove (const std::vector< double > &from_joint_pose, const std::vector< double > &to_joint_pose, double dt) const |
Check that the time to move between two waypoints is sufficient given velocity limits. | |
bool | isValidVelocityMove (const double *from_joint_pose, const double *to_joint_pose, std::size_t array_size, double dt) const |
Check that the time to move between two waypoints is sufficient given velocity limits. | |
bool | computeJointVariableIndices (const std::vector< std::string > &joint_names, std::vector< size_t > &joint_bijection) const |
Computes the indices of joint variables given a vector of joint names to look up. | |
std::pair< Eigen::VectorXd, Eigen::VectorXd > | getLowerAndUpperLimits () const |
Get the lower and upper position limits of all active variables in the group. | |
std::pair< Eigen::VectorXd, Eigen::VectorXd > | getMaxVelocitiesAndAccelerationBounds () const |
Gets the pair of maximum joint velocities/accelerations for a given group. Asserts that the group contains only single-variable joints,. | |
Protected Member Functions | |
void | updateMimicJoints (double *values) const |
Update the variable values for the state of a group with respect to the mimic joints. This only updates mimic joints that have the parent in this group. If there is a joint mimicking one that is outside the group, there are no values to be read (values is only the group state) | |
Protected Attributes | |
const RobotModel * | parent_model_ |
Owner model. | |
std::string | name_ |
Name of group. | |
std::vector< const JointModel * > | joint_model_vector_ |
Joint instances in the order they appear in the group state. | |
std::vector< std::string > | joint_model_name_vector_ |
Names of joints in the order they appear in the group state. | |
std::vector< const JointModel * > | active_joint_model_vector_ |
Active joint instances in the order they appear in the group state. | |
std::vector< std::string > | active_joint_model_name_vector_ |
Names of active joints in the order they appear in the group state. | |
std::vector< const JointModel * > | fixed_joints_ |
The joints that have no DOF (fixed) | |
std::vector< const JointModel * > | mimic_joints_ |
Joints that mimic other joints. | |
std::vector< const JointModel * > | continuous_joint_model_vector_ |
The set of continuous joints this group contains. | |
std::vector< std::string > | 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 > | 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!) | |
JointModelMapConst | joint_model_map_ |
A map from joint names to their instances. This includes all joints in the group. | |
std::vector< const JointModel * > | joint_roots_ |
The list of active joint models that are roots in this group. | |
const JointModel * | common_root_ |
The joint that is a common root for all joints in this group (not necessarily part of this group) | |
VariableIndexMap | 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. Additionally, it includes the names of the joints and the index for the first variable of that joint. | |
JointBoundsVector | active_joint_models_bounds_ |
The bounds for all the active joint models. | |
std::vector< int > | variable_index_list_ |
The list of index values this group includes, with respect to a full robot state; this includes mimic joints. | |
std::vector< int > | active_joint_model_start_index_ |
For each active joint model in this group, hold the index at which the corresponding joint state starts in the group state. | |
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. | |
LinkModelMapConst | link_model_map_ |
A map from link names to their instances. | |
std::vector< std::string > | link_model_name_vector_ |
The names of the links in this group. | |
std::vector< const LinkModel * > | link_model_with_geometry_vector_ |
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 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< 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< 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< 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< 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) | |
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< 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< 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) | |
unsigned int | variable_count_ |
The number of variables necessary to describe this group of joints. | |
unsigned int | active_variable_count_ |
The number of variables necessary to describe the active joints in this group of joints. | |
bool | is_contiguous_index_list_ |
True if the state of this group is contiguous within the full robot state; this also means that the index values in variable_index_list_ are consecutive integers. | |
std::vector< std::string > | subgroup_names_ |
The set of labelled subgroups that are included in this group. | |
std::set< std::string > | subgroup_names_set_ |
The set of labelled subgroups that are included in this group. | |
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::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::string | end_effector_name_ |
The name of the end effector, if this group is an end-effector. | |
bool | is_chain_ |
bool | is_single_dof_ |
std::vector< GroupMimicUpdate > | group_mimic_update_ |
std::pair< KinematicsSolver, KinematicsSolverMap > | group_kinematics_ |
srdf::Model::Group | config_ |
std::map< std::string, std::map< std::string, double > > | default_states_ |
The set of default states specified for this group in the SRDF. | |
std::vector< std::string > | default_states_names_ |
The names of the default states specified for this group in the SRDF. | |
Definition at line 69 of file joint_model_group.h.
using moveit::core::JointModelGroup::KinematicsSolverMap = std::map<const JointModelGroup*, KinematicsSolver> |
Map from group instances to allocator functions & bijections.
Definition at line 106 of file joint_model_group.h.
moveit::core::JointModelGroup::JointModelGroup | ( | const std::string & | name, |
const srdf::Model::Group & | config, | ||
const std::vector< const JointModel * > & | joint_vector, | ||
const RobotModel * | parent_model | ||
) |
|
default |
void moveit::core::JointModelGroup::addDefaultState | ( | const std::string & | name, |
const std::map< std::string, double > & | default_state | ||
) |
Definition at line 495 of file joint_model_group.cpp.
void moveit::core::JointModelGroup::attachEndEffector | ( | const std::string & | eef_name | ) |
Notify this group that there is an end-effector attached to it.
Definition at line 536 of file joint_model_group.cpp.
bool moveit::core::JointModelGroup::canSetStateFromIK | ( | const std::string & | tip | ) | const |
bool moveit::core::JointModelGroup::computeJointVariableIndices | ( | const std::vector< std::string > & | joint_names, |
std::vector< size_t > & | joint_bijection | ||
) | const |
Computes the indices of joint variables given a vector of joint names to look up.
Definition at line 621 of file joint_model_group.cpp.
double moveit::core::JointModelGroup::distance | ( | const double * | state1, |
const double * | state2 | ||
) | const |
|
inline |
Definition at line 386 of file joint_model_group.h.
bool moveit::core::JointModelGroup::enforcePositionBounds | ( | double * | state, |
const JointBoundsVector & | active_joint_bounds | ||
) | 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 164 of file joint_model_group.h.
|
inline |
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
Definition at line 157 of file joint_model_group.h.
|
inline |
Get the bounds for all the active joints.
Definition at line 519 of file joint_model_group.h.
|
inline |
Get the number of variables that describe the active joints in this joint group. This excludes variables necessary for mimic joints.
Definition at line 417 of file joint_model_group.h.
|
inline |
Get the names of the end effectors attached to this group.
Definition at line 488 of file joint_model_group.h.
|
inline |
Get the common root of all joint roots; not necessarily part of this group.
Definition at line 207 of file joint_model_group.h.
|
inline |
get the SRDF configuration this group is based on
Definition at line 126 of file joint_model_group.h.
|
inline |
Get the array of continuous joints used in this group (may include mimic joints).
Definition at line 182 of file joint_model_group.h.
|
inline |
Get the default IK timeout.
Definition at line 557 of file joint_model_group.h.
|
inline |
Get the names of the known default states (as specified in the SRDF)
Definition at line 295 of file joint_model_group.h.
|
inline |
Return the name of the end effector, if this group is an end-effector.
Definition at line 464 of file joint_model_group.h.
|
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 482 of file joint_model_group.h.
bool moveit::core::JointModelGroup::getEndEffectorTips | ( | std::vector< const LinkModel * > & | tips | ) | const |
Get the unique set of end effector tips included in a particular joint model group as defined by the SRDF end effector elements e.g. for a humanoid robot this would return 4 tips for the hands and feet.
tips | - the output vector of link models of the tips |
Definition at line 555 of file joint_model_group.cpp.
bool moveit::core::JointModelGroup::getEndEffectorTips | ( | std::vector< std::string > & | tips | ) | const |
Get the unique set of end effector tips included in a particular joint model group as defined by the SRDF end effector elements e.g. for a humanoid robot this would return 4 tips for the hands and feet.
tips | - the output vector of link names of the tips |
Definition at line 541 of file joint_model_group.cpp.
|
inline |
Get the fixed joints that are part of this group.
Definition at line 170 of file joint_model_group.h.
|
inline |
const JointModel * moveit::core::JointModelGroup::getJointModel | ( | const std::string & | joint | ) | const |
Get a joint by its name. Throw an exception if the joint is not part of this group.
Definition at line 337 of file joint_model_group.cpp.
|
inline |
Get the names of the joints in this group. These are the names of the joints returned by getJointModels().
Definition at line 151 of file joint_model_group.h.
|
inline |
Get all the joints in this group (including fixed and mimic joints).
Definition at line 144 of file joint_model_group.h.
|
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 201 of file joint_model_group.h.
|
inline |
Return the mapping between the order of the joints in this group and the order of the joints in the kinematics solver. An element bijection[i] at index i in this array, maps the variable at index bijection[i] in this group to the variable at index i in the kinematic solver.
Definition at line 569 of file joint_model_group.h.
const LinkModel * moveit::core::JointModelGroup::getLinkModel | ( | const std::string & | link | ) | const |
Get a link by its name. Throw an exception if the link is not part of this group.
Definition at line 326 of file joint_model_group.cpp.
|
inline |
Get the names of the links that are part of this joint group.
Definition at line 219 of file joint_model_group.h.
|
inline |
Get the names of the links that are part of this joint group and also have geometry associated with them.
Definition at line 225 of file joint_model_group.h.
|
inline |
Get the links that are part of this joint group.
Definition at line 213 of file joint_model_group.h.
std::pair< Eigen::VectorXd, Eigen::VectorXd > moveit::core::JointModelGroup::getLowerAndUpperLimits | ( | ) | const |
Get the lower and upper position limits of all active variables in the group.
Definition at line 835 of file joint_model_group.cpp.
|
inline |
Definition at line 399 of file joint_model_group.h.
double moveit::core::JointModelGroup::getMaximumExtent | ( | const JointBoundsVector & | active_joint_bounds | ) | const |
Definition at line 451 of file joint_model_group.cpp.
std::pair< Eigen::VectorXd, Eigen::VectorXd > moveit::core::JointModelGroup::getMaxVelocitiesAndAccelerationBounds | ( | ) | const |
Gets the pair of maximum joint velocities/accelerations for a given group. Asserts that the group contains only single-variable joints,.
In case of asymmetric velocity or acceleration limits, this function will return the most limiting component.
Definition at line 853 of file joint_model_group.cpp.
|
inline |
Get the mimic joints that are part of this group.
Definition at line 176 of file joint_model_group.h.
|
inline |
Get the name of the joint group.
Definition at line 120 of file joint_model_group.h.
const LinkModel * moveit::core::JointModelGroup::getOnlyOneEndEffectorTip | ( | ) | const |
Get one end effector tip, throwing an error if there ends up being more in the joint model group This is a useful helper function because most planning groups (almost all) only have one tip.
Definition at line 582 of file joint_model_group.cpp.
|
inline |
Get the kinematic model this group is part of.
Definition at line 114 of file joint_model_group.h.
|
inline |
Definition at line 542 of file joint_model_group.h.
|
inline |
|
inline |
Get the names of the groups that are subsets of this one (in terms of joints set)
Definition at line 426 of file joint_model_group.h.
void moveit::core::JointModelGroup::getSubgroups | ( | std::vector< const JointModelGroup * > & | sub_groups | ) | const |
Get the groups that are subsets of this one (in terms of joints set)
Definition at line 309 of file joint_model_group.cpp.
|
inline |
Get the names of the links returned by getUpdatedLinkModels()
Definition at line 246 of file joint_model_group.h.
|
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 234 of file joint_model_group.h.
|
inline |
Return the same data as getUpdatedLinkModels() but as a set.
Definition at line 240 of file joint_model_group.h.
|
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 254 of file joint_model_group.h.
|
inline |
Get the names of the links returned by getUpdatedLinkModels()
Definition at line 266 of file joint_model_group.h.
|
inline |
Get the names of the links returned by getUpdatedLinkModels()
Definition at line 272 of file joint_model_group.h.
|
inline |
Return the same data as getUpdatedLinkModelsWithGeometry() but as a set.
Definition at line 260 of file joint_model_group.h.
|
inline |
Get the number of variables that describe this joint group. This includes variables necessary for mimic joints, so will always be >= getActiveVariableCount()
Definition at line 410 of file joint_model_group.h.
bool moveit::core::JointModelGroup::getVariableDefaultPositions | ( | 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 501 of file joint_model_group.cpp.
void moveit::core::JointModelGroup::getVariableDefaultPositions | ( | double * | values | ) | const |
Compute the default values for the joint group.
Definition at line 510 of file joint_model_group.cpp.
void moveit::core::JointModelGroup::getVariableDefaultPositions | ( | std::map< std::string, double > & | values | ) | const |
Compute the default values for the joint group.
Definition at line 517 of file joint_model_group.cpp.
|
inline |
Compute the default values for the joint group.
Definition at line 309 of file joint_model_group.h.
int moveit::core::JointModelGroup::getVariableGroupIndex | ( | const std::string & | variable | ) | const |
Get the index of a variable within the group. Return -1 on error.
Definition at line 601 of file joint_model_group.cpp.
|
inline |
Get the index locations in the complete robot state for all the variables in this group.
Definition at line 286 of file joint_model_group.h.
|
inline |
Get the names of the variables that make up the joints included in this group. The number of returned elements is always equal to getVariableCount(). This includes mimic joints.
Definition at line 189 of file joint_model_group.h.
|
inline |
Compute random values for the state of the joint group.
Definition at line 319 of file joint_model_group.h.
void moveit::core::JointModelGroup::getVariableRandomPositions | ( | random_numbers::RandomNumberGenerator & | rng, |
double * | values, | ||
const JointBoundsVector & | active_joint_bounds | ||
) | const |
|
inline |
Compute random values for the state of the joint group.
Definition at line 325 of file joint_model_group.h.
|
inline |
Compute random values for the state of the joint group.
Definition at line 332 of file joint_model_group.h.
|
inline |
Compute random values for the state of the joint group.
Definition at line 355 of file joint_model_group.h.
void moveit::core::JointModelGroup::getVariableRandomPositionsNearBy | ( | random_numbers::RandomNumberGenerator & | rng, |
double * | values, | ||
const JointBoundsVector & | active_joint_bounds, | ||
const double * | near, | ||
const double | distance | ||
) | const |
Compute random values for the state of the joint group.
Definition at line 361 of file joint_model_group.cpp.
void moveit::core::JointModelGroup::getVariableRandomPositionsNearBy | ( | random_numbers::RandomNumberGenerator & | rng, |
double * | values, | ||
const JointBoundsVector & | active_joint_bounds, | ||
const double * | near, | ||
const std::map< JointModel::JointType, double > & | distance_map | ||
) | const |
Compute random values for the state of the joint group.
Definition at line 376 of file joint_model_group.cpp.
void moveit::core::JointModelGroup::getVariableRandomPositionsNearBy | ( | random_numbers::RandomNumberGenerator & | rng, |
double * | values, | ||
const JointBoundsVector & | active_joint_bounds, | ||
const double * | near, | ||
const std::vector< double > & | distances | ||
) | const |
Compute random values for the state of the joint group.
Definition at line 402 of file joint_model_group.cpp.
|
inline |
Compute random values for the state of the joint group.
Definition at line 346 of file joint_model_group.h.
|
inline |
Compute random values for the state of the joint group.
Definition at line 361 of file joint_model_group.h.
|
inline |
Compute random values for the state of the joint group.
Definition at line 338 of file joint_model_group.h.
bool moveit::core::JointModelGroup::hasJointModel | ( | const std::string & | joint | ) | const |
Check if a joint is part of this group.
Definition at line 316 of file joint_model_group.cpp.
bool moveit::core::JointModelGroup::hasLinkModel | ( | const std::string & | link | ) | const |
Check if a link is part of this group.
Definition at line 321 of file joint_model_group.cpp.
void moveit::core::JointModelGroup::interpolate | ( | const double * | from, |
const double * | to, | ||
double | t, | ||
double * | state | ||
) | const |
Definition at line 474 of file joint_model_group.cpp.
|
inline |
Check if this group is a linear chain.
Definition at line 441 of file joint_model_group.h.
|
inline |
|
inline |
Check if this group was designated as an end-effector in the SRDF.
Definition at line 453 of file joint_model_group.h.
|
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 280 of file joint_model_group.h.
|
inline |
Return true if the group consists only of joints that are single DOF.
Definition at line 447 of file joint_model_group.h.
|
inline |
Check if the joints of group group are a subset of the joints in this group.
Definition at line 435 of file joint_model_group.h.
bool moveit::core::JointModelGroup::isValidVelocityMove | ( | const double * | from_joint_pose, |
const double * | to_joint_pose, | ||
std::size_t | array_size, | ||
double | dt | ||
) | const |
Check that the time to move between two waypoints is sufficient given velocity limits.
Definition at line 804 of file joint_model_group.cpp.
bool moveit::core::JointModelGroup::isValidVelocityMove | ( | const std::vector< double > & | from_joint_pose, |
const std::vector< double > & | to_joint_pose, | ||
double | dt | ||
) | const |
Check that the time to move between two waypoints is sufficient given velocity limits.
Definition at line 791 of file joint_model_group.cpp.
void moveit::core::JointModelGroup::printGroupInfo | ( | std::ostream & | out = std::cout | ) | const |
Print information about the constructed model.
Definition at line 728 of file joint_model_group.cpp.
bool moveit::core::JointModelGroup::satisfiesPositionBounds | ( | const double * | state, |
const JointBoundsVector & | active_joint_bounds, | ||
double | margin = 0.0 |
||
) | const |
|
inline |
Definition at line 392 of file joint_model_group.h.
void moveit::core::JointModelGroup::setDefaultIKTimeout | ( | double | ik_timeout | ) |
Set the default IK timeout.
Definition at line 612 of file joint_model_group.cpp.
void moveit::core::JointModelGroup::setEndEffectorName | ( | const std::string & | name | ) |
Set the name of the end-effector, and remember this group is indeed an end-effector.
Definition at line 525 of file joint_model_group.cpp.
void moveit::core::JointModelGroup::setEndEffectorParent | ( | const std::string & | group, |
const std::string & | link | ||
) |
If this group is an end-effector, specify the parent group (e.g., the arm holding the eef) and the link the end effector connects to.
Definition at line 530 of file joint_model_group.cpp.
|
inline |
Definition at line 549 of file joint_model_group.h.
|
inline |
Definition at line 529 of file joint_model_group.h.
void moveit::core::JointModelGroup::setSolverAllocators | ( | const std::pair< SolverAllocatorFn, SolverAllocatorMapFn > & | solvers | ) |
void moveit::core::JointModelGroup::setSubgroupNames | ( | const std::vector< std::string > & | subgroups | ) |
Set the names of the subgroups for this group.
Definition at line 301 of file joint_model_group.cpp.
|
protected |
Update the variable values for the state of a group with respect to the mimic joints. This only updates mimic joints that have the parent in this group. If there is a joint mimicking one that is outside the group, there are no values to be read (values is only the group state)
Definition at line 488 of file joint_model_group.cpp.
|
protected |
Names of active joints in the order they appear in the group state.
Definition at line 626 of file joint_model_group.h.
|
protected |
For each active joint model in this group, hold the index at which the corresponding joint state starts in the group state.
Definition at line 668 of file joint_model_group.h.
|
protected |
Active joint instances in the order they appear in the group state.
Definition at line 623 of file joint_model_group.h.
|
protected |
The bounds for all the active joint models.
Definition at line 660 of file joint_model_group.h.
|
protected |
The number of variables necessary to describe the active joints in this group of joints.
Definition at line 722 of file joint_model_group.h.
|
protected |
If an end-effector is attached to this group, the name of that end-effector is stored in this variable.
Definition at line 735 of file joint_model_group.h.
|
protected |
The joint that is a common root for all joints in this group (not necessarily part of this group)
Definition at line 652 of file joint_model_group.h.
|
protected |
Definition at line 764 of file joint_model_group.h.
|
protected |
The set of continuous joints this group contains.
Definition at line 635 of file joint_model_group.h.
|
protected |
The set of default states specified for this group in the SRDF.
Definition at line 767 of file joint_model_group.h.
|
protected |
The names of the default states specified for this group in the SRDF.
Definition at line 770 of file joint_model_group.h.
|
protected |
The name of the end effector, if this group is an end-effector.
Definition at line 743 of file joint_model_group.h.
|
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 740 of file joint_model_group.h.
|
protected |
The joints that have no DOF (fixed)
Definition at line 629 of file joint_model_group.h.
|
protected |
Definition at line 762 of file joint_model_group.h.
|
protected |
Definition at line 760 of file joint_model_group.h.
|
protected |
Definition at line 745 of file joint_model_group.h.
|
protected |
True if the state of this group is contiguous within the full robot state; this also means that the index values in variable_index_list_ are consecutive integers.
Definition at line 726 of file joint_model_group.h.
|
protected |
Definition at line 747 of file joint_model_group.h.
|
protected |
A map from joint names to their instances. This includes all joints in the group.
Definition at line 646 of file joint_model_group.h.
|
protected |
Names of joints in the order they appear in the group state.
Definition at line 620 of file joint_model_group.h.
|
protected |
Joint instances in the order they appear in the group state.
Definition at line 617 of file joint_model_group.h.
|
protected |
The list of active joint models that are roots in this group.
Definition at line 649 of file joint_model_group.h.
|
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. Additionally, it includes the names of the joints and the index for the first variable of that joint.
Definition at line 657 of file joint_model_group.h.
|
protected |
A map from link names to their instances.
Definition at line 676 of file joint_model_group.h.
|
protected |
The names of the links in this group.
Definition at line 679 of file joint_model_group.h.
|
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 673 of file joint_model_group.h.
|
protected |
The names of the links in this group that also have geometry.
Definition at line 684 of file joint_model_group.h.
|
protected |
Definition at line 681 of file joint_model_group.h.
|
protected |
Joints that mimic other joints.
Definition at line 632 of file joint_model_group.h.
|
protected |
Name of group.
Definition at line 614 of file joint_model_group.h.
|
protected |
Owner model.
Definition at line 611 of file joint_model_group.h.
|
protected |
The set of labelled subgroups that are included in this group.
Definition at line 729 of file joint_model_group.h.
|
protected |
The set of labelled subgroups that are included in this group.
Definition at line 732 of file joint_model_group.h.
|
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 700 of file joint_model_group.h.
|
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 696 of file joint_model_group.h.
|
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 692 of file joint_model_group.h.
|
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 688 of file joint_model_group.h.
|
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 716 of file joint_model_group.h.
|
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 712 of file joint_model_group.h.
|
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 708 of file joint_model_group.h.
|
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 704 of file joint_model_group.h.
|
protected |
The number of variables necessary to describe this group of joints.
Definition at line 719 of file joint_model_group.h.
|
protected |
The list of index values this group includes, with respect to a full robot state; this includes mimic joints.
Definition at line 664 of file joint_model_group.h.
|
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 639 of file joint_model_group.h.
|
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 643 of file joint_model_group.h.