42 #include <boost/lexical_cast.hpp> 44 #include "order_robot_model_items.inc" 53 bool includesParent(
const JointModel* joint,
const JointModelGroup* group)
57 while (joint->getParentLinkModel() !=
nullptr)
59 joint = joint->getParentLinkModel()->getParentJointModel();
60 if (group->hasJointModel(joint->getName()) && joint->getVariableCount() > 0 && joint->getMimic() ==
nullptr)
65 else if (joint->getMimic() !=
nullptr)
67 const JointModel* mjoint = joint->getMimic();
68 if (group->hasJointModel(mjoint->getName()) && mjoint->getVariableCount() > 0 && mjoint->getMimic() ==
nullptr)
70 else if (includesParent(mjoint, group))
80 bool jointPrecedes(
const JointModel* a,
const JointModel* b)
82 if (!a->getParentLinkModel())
84 const JointModel* p = a->getParentLinkModel()->getParentJointModel();
90 p = p->getParentLinkModel() ? p->getParentLinkModel()->getParentJointModel() :
nullptr;
100 const std::vector<const JointModel*>& unsorted_group_joints,
102 : parent_model_(parent_model)
104 , common_root_(nullptr)
106 , is_contiguous_index_list_(true)
108 , is_single_dof_(true)
122 unsigned int vc = joint_model_vector_[i]->getVariableCount();
127 const std::vector<std::string>& name_order = joint_model_vector_[i]->getVariableNames();
128 if (joint_model_vector_[i]->getMimic() ==
nullptr)
137 for (std::size_t j = 0; j < name_order.size(); ++j)
143 int first_index = joint_model_vector_[i]->getFirstVariableIndex();
144 for (std::size_t j = 0; j < name_order.size(); ++j)
152 static_cast<const RevoluteJointModel*>(joint_model_vector_[i])->isContinuous())
189 GroupMimicUpdate mu(src, dest, mimic_joints_[i]->getMimicFactor(), mimic_joints_[i]->getMimicOffset());
194 std::set<const LinkModel*> group_links_set;
197 for (std::set<const LinkModel*>::iterator it = group_links_set.begin(); it != group_links_set.end(); ++it)
205 if (!link_model_vector_[i]->getShapes().empty())
223 const std::vector<const LinkModel*>& links =
joint_roots_[i]->getDescendantLinkModels();
231 if (!(*it)->getShapes().empty())
240 OrderLinksByIndex());
295 ROS_ERROR_NAMED(
"robot_model.jmg",
"Link '%s' not found in group '%s'", name.c_str(),
name_.c_str());
306 ROS_ERROR_NAMED(
"robot_model.jmg",
"Joint '%s' not found in group '%s'", name.c_str(),
name_.c_str());
318 *active_joint_bounds[i]);
337 const double* near,
const std::map<JointModel::JointType, double>& distance_map)
const 343 std::map<JointModel::JointType, double>::const_iterator iter =
345 if (iter != distance_map.end())
346 distance = iter->second;
348 ROS_WARN_NAMED(
"robot_model.jmg",
"Did not pass in distance for '%s'",
359 const std::vector<double>& distances)
const 363 throw Exception(
"When sampling random values nearby for group '" +
name_ +
364 "', distances vector should be of size " +
366 boost::lexical_cast<std::string>(distances.size()));
380 *active_joint_bounds[i], margin))
391 *active_joint_bounds[i]))
400 double max_distance = 0.0;
445 std::map<std::string, std::map<std::string, double> >::const_iterator it =
default_states_.find(name);
486 std::vector<const LinkModel*> tip_links;
492 for (std::size_t i = 0; i < tip_links.size(); ++i)
494 tips.push_back(tip_links[i]->
getName());
506 ROS_ERROR_NAMED(
"robot_model.jmg",
"Unable to find joint model group for eef");
514 ROS_ERROR_NAMED(
"robot_model.jmg",
"Unable to find end effector link for eef");
518 tips.push_back(eef_link);
525 std::vector<const LinkModel*> tips;
527 if (tips.size() == 1)
529 else if (tips.size() > 1)
530 ROS_ERROR_NAMED(
"robot_model.jmg",
"More than one end effector tip found for joint model group, " 531 "so cannot return only one");
533 ROS_ERROR_NAMED(
"robot_model.jmg",
"No end effector tips found in joint model group");
542 ROS_ERROR_NAMED(
"robot_model.jmg",
"Variable '%s' is not part of group '%s'", variable.c_str(),
name_.c_str());
554 it->second.default_ik_timeout_ = ik_timeout;
561 it->second.default_ik_attempts_ = ik_attempts;
565 std::vector<unsigned int>& joint_bijection)
const 567 joint_bijection.clear();
568 for (std::size_t i = 0; i < ik_jnames.size(); ++i)
576 ROS_ERROR_NAMED(
"robot_model.jmg",
"IK solver computes joint values for joint '%s' " 577 "but group '%s' does not contain such a joint.",
578 ik_jnames[i].c_str(),
getName().c_str());
583 joint_bijection.push_back(it->second + k);
605 for (SolverAllocatorMapFn::const_iterator it = solvers.second.begin(); it != solvers.second.end(); ++it)
606 if (it->first->getSolverInstance())
625 if (!solver || tip.empty())
628 const std::vector<std::string>& tip_frames = solver->getTipFrames();
630 if (tip_frames.empty())
637 for (std::size_t i = 0; i < tip_frames.size(); ++i)
640 const std::string& tip_local = tip[0] ==
'/' ? tip.substr(1) : tip;
641 const std::string& tip_frame_local = tip_frames[i][0] ==
'/' ? tip_frames[i].substr(1) : tip_frames[i];
642 ROS_DEBUG_NAMED(
"robot_model.jmg",
"comparing input tip: %s to this groups tip: %s ", tip_local.c_str(),
643 tip_frame_local.c_str());
646 if (tip_local != tip_frame_local)
654 for (LinkTransformMap::const_iterator it = fixed_links.begin(); it != fixed_links.end(); ++it)
656 if (it->first->getName() == tip_local)
672 out <<
" * Joints:" << std::endl;
676 out <<
" * Variables:" << std::endl;
683 << local_idx <<
" in group state";
689 out <<
" * Variables Index List:" << std::endl;
694 out <<
"(contiguous)";
696 out <<
"(non-contiguous)";
700 out <<
" * Kinematics solver bijection:" << std::endl;
708 out <<
" * Compound kinematics solver:" << std::endl;
712 out <<
" " << it->first->getName() <<
":";
713 for (std::size_t i = 0; i < it->second.bijection_.size(); ++i)
714 out <<
" " << it->second.bijection_[i];
721 out <<
" * Local Mimic Updates:" << std::endl;
SolverAllocatorFn allocator_
Function type that allocates a kinematics solver for a particular group.
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)
const std::string & getName() const
Get the name of the joint.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
bool hasJointModel(const std::string &joint) const
Check if a joint is part of this group.
const kinematics::KinematicsBaseConstPtr & getSolverInstance() const
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 no...
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 li...
std::vector< GroupMimicUpdate > group_mimic_update_
std::vector< std::string > subgroup_names_
The set of labelled subgroups that are included in this group.
std::vector< const JointModel * > joint_model_vector_
Joint instances in the order they appear in the group state.
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.
int getVariableGroupIndex(const std::string &variable) const
Get the index of a variable within the group. Return -1 on error.
#define ROS_WARN_NAMED(name,...)
bool enforcePositionBounds(double *state, const JointBoundsVector &active_joint_bounds) const
const JointModel * getJointOfVariable(int variable_index) const
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 no...
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...
std::map< std::string, std::map< std::string, double > > default_states_
The set of default states specified for this group in the SRDF.
unsigned int variable_count_
The number of variables necessary to describe this group of joints.
const LinkModel * getLinkModel(const std::string &link) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
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 ne...
const std::string & getName() const
Get the name of the joint group.
const LinkModel * getLinkModel(const std::string &link) const
Get a link by its name. Output error and return NULL when the link is missing.
std::vector< std::string > active_joint_model_name_vector_
Names of active joints in the order they appear in the group state.
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a specific variable. Throw an exception of variable is not found.
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...
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.
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 grou...
double getMaximumExtent() const
bool canSetStateFromIK(const std::string &tip) const
bool getEndEffectorTips(std::vector< const LinkModel * > &tips) const
Get a vector of end effector tips included in a particular joint model group as defined by the SRDF e...
int getLocalVariableIndex(const std::string &variable) const
Get the index of the variable within this joint.
std::map< const LinkModel *, Eigen::Affine3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Affine3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
std::vector< const JointModel * > joint_roots_
The list of active joint models that are roots in this group.
std::string name_
Name of group.
std::vector< std::string > joint_model_name_vector_
Names of joints in the order they appear in the group state.
bool is_contiguous_index_list_
True if the state of this group is contiguous within the full robot state; this also means that the i...
const JointModelGroup * getEndEffector(const std::string &name) const
Get the joint group that corresponds to a given end-effector name.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
std::vector< int > variable_index_list_
The list of index values this group includes, with respect to a full robot state; this includes mimic...
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
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 no...
void addDefaultState(const std::string &name, const std::map< std::string, double > &default_state)
std::vector< std::string > default_states_names_
The names of the default states specified for this group in the SRDF.
void setDefaultIKTimeout(double ik_timeout)
Set the default IK timeout.
std::vector< const LinkModel * > link_model_with_geometry_vector_
void interpolate(const double *from, const double *to, double t, double *state) const
JointModelMapConst joint_model_map_
A map from joint names to their instances. This includes all joints in the group. ...
void setEndEffectorName(const std::string &name)
Set the name of the end-effector, and remember this group is indeed an end-effector.
#define ROS_DEBUG_NAMED(name,...)
unsigned int default_ik_attempts_
std::vector< const JointModel * > mimic_joints_
Joints that mimic other joints.
void setSubgroupNames(const std::vector< std::string > &subgroups)
Set the names of the subgroups for this group.
std::vector< std::string > link_model_name_vector_
The names of the links 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...
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute random values for the state of the joint group.
JointModelGroup(const std::string &name, const srdf::Model::Group &config, const std::vector< const JointModel * > &joint_vector, const RobotModel *parent_model)
const RobotModel * parent_model_
Owner model.
std::vector< const JointModel::Bounds * > JointBoundsVector
double getMaximumExtent(const JointBoundsVector &active_joint_bounds) const
This may be thrown if unrecoverable errors occur.
VariableIndexMap joint_variables_index_map_
The group includes all the joint variables that make up the joints the group consists of...
std::pair< KinematicsSolver, KinematicsSolverMap > group_kinematics_
JointBoundsVector active_joint_models_bounds_
The bounds for all the active joint models.
void attachEndEffector(const std::string &eef_name)
Notify this group that there is an end-effector attached to it.
void setSolverAllocators(const SolverAllocatorFn &solver, const SolverAllocatorMapFn &solver_map=SolverAllocatorMapFn())
const std::vector< std::string > & getAttachedEndEffectorNames() const
Get the names of the end effectors attached to this group.
std::vector< const JointModel * > fixed_joints_
The joints that have no DOF (fixed)
kinematics::KinematicsBaseConstPtr solver_instance_const_
std::vector< unsigned int > bijection_
The mapping between the order of the joints in the group and the order of the joints in the kinematic...
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
bool hasLinkModel(const std::string &link) const
Check if a link is part of this group.
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...
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 variabl...
std::string end_effector_name_
The name of the end effector, if this group is an end-effector.
bool enforcePositionBounds(double *state) const
kinematics::KinematicsBasePtr solver_instance_
void printGroupInfo(std::ostream &out=std::cout) const
Print information about the constructed model.
LinkModelMapConst link_model_map_
A map from link names to their instances.
int getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
bool computeIKIndexBijection(const std::vector< std::string > &ik_jnames, std::vector< unsigned int > &joint_bijection) const
std::vector< const JointModel * > continuous_joint_model_vector_
The set of continuous joints this group contains.
std::vector< const JointModel * > active_joint_model_vector_
Active joint instances in the order they appear in the group state.
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 ne...
double default_ik_timeout_
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 star...
std::set< std::string > subgroup_names_set_
The set of labelled subgroups that are included in this group.
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...
#define ROS_ERROR_NAMED(name,...)
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms.
const JointModel * common_root_
The joint that is a common root for all joints in this group (not necessarily part of this group) ...
A link from the robot. Contains the constant transform applied to the link and its geometry...
double distance(const double *state1, const double *state2) const
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 pare...
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...
Main namespace for MoveIt!
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 no...
void setDefaultIKAttempts(unsigned int ik_attempts)
Set the default IK attempts.
JointType getType() const
Get the type of joint.
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...
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 ...
void getSubgroups(std::vector< const JointModelGroup * > &sub_groups) const
Get the groups that are subsets of this one (in terms of joints set)
bool satisfiesPositionBounds(const double *state, double margin=0.0) const
const JointModel * getMimic() const
Get the joint this one is mimicking.