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;
 
   99 const std::string 
LOGNAME = 
"robot_model.jmg";
 
  102                                  const std::vector<const JointModel*>& unsorted_group_joints,
 
  103                                  const RobotModel* parent_model)
 
  104   : parent_model_(parent_model)
 
  106   , common_root_(nullptr)
 
  108   , active_variable_count_(0)
 
  109   , is_contiguous_index_list_(true)
 
  111   , is_single_dof_(true)
 
  115   joint_model_vector_ = unsorted_group_joints;
 
  116   std::sort(joint_model_vector_.begin(), joint_model_vector_.end(), OrderJointsByIndex());
 
  117   joint_model_name_vector_.reserve(joint_model_vector_.size());
 
  121   for (
const JointModel* joint_model : joint_model_vector_)
 
  123     joint_model_name_vector_.push_back(joint_model->getName());
 
  124     joint_model_map_[joint_model->getName()] = joint_model;
 
  125     unsigned int vc = joint_model->getVariableCount();
 
  129         is_single_dof_ = 
false;
 
  130       const std::vector<std::string>& name_order = joint_model->getVariableNames();
 
  131       if (joint_model->getMimic() == 
nullptr)
 
  133         active_joint_model_vector_.push_back(joint_model);
 
  134         active_joint_model_name_vector_.push_back(joint_model->getName());
 
  135         active_joint_model_start_index_.push_back(variable_count_);
 
  136         active_joint_models_bounds_.push_back(&joint_model->getVariableBounds());
 
  137         active_variable_count_ += vc;
 
  140         mimic_joints_.push_back(joint_model);
 
  141       for (
const std::string& name : name_order)
 
  144         variable_names_set_.insert(name);
 
  147       int first_index = joint_model->getFirstVariableIndex();
 
  148       for (std::size_t j = 0; j < name_order.size(); ++j)
 
  150         variable_index_list_.push_back(first_index + j);
 
  151         joint_variables_index_map_[name_order[j]] = variable_count_ + j;
 
  153       joint_variables_index_map_[joint_model->getName()] = variable_count_;
 
  156           static_cast<const RevoluteJointModel*
>(joint_model)->isContinuous())
 
  157         continuous_joint_model_vector_.push_back(joint_model);
 
  159       variable_count_ += vc;
 
  162       fixed_joints_.push_back(joint_model);
 
  167   for (
const JointModel* active_joint_model : active_joint_model_vector_)
 
  170     if (!includesParent(active_joint_model, 
this))
 
  171       joint_roots_.push_back(active_joint_model);
 
  176   if (variable_index_list_.empty())
 
  177     is_contiguous_index_list_ = 
false;
 
  179     for (std::size_t i = 1; i < variable_index_list_.size(); ++i)
 
  180       if (variable_index_list_[i] != variable_index_list_[i - 1] + 1)
 
  182         is_contiguous_index_list_ = 
false;
 
  187   for (
const JointModel* mimic_joint : mimic_joints_)
 
  189     if (hasJointModel(mimic_joint->getMimic()->getName()))
 
  191       int src = joint_variables_index_map_[mimic_joint->getMimic()->getName()];
 
  192       int dest = joint_variables_index_map_[mimic_joint->getName()];
 
  193       GroupMimicUpdate mu(src, dest, mimic_joint->getMimicFactor(), mimic_joint->getMimicOffset());
 
  194       group_mimic_update_.push_back(mu);
 
  198   std::set<const LinkModel*> group_links_set;
 
  199   for (
const JointModel* joint_model : joint_model_vector_)
 
  200     group_links_set.insert(joint_model->getChildLinkModel());
 
  201   for (
const LinkModel* group_link : group_links_set)
 
  202     link_model_vector_.push_back(group_link);
 
  203   std::sort(link_model_vector_.begin(), link_model_vector_.end(), OrderLinksByIndex());
 
  205   for (
const LinkModel* link_model : link_model_vector_)
 
  207     link_model_map_[link_model->getName()] = link_model;
 
  208     link_model_name_vector_.push_back(link_model->getName());
 
  209     if (!link_model->getShapes().empty())
 
  211       link_model_with_geometry_vector_.push_back(link_model);
 
  212       link_model_with_geometry_name_vector_.push_back(link_model->getName());
 
  217   if (!joint_roots_.empty())
 
  219     common_root_ = joint_roots_[0];
 
  220     for (std::size_t i = 1; i < joint_roots_.size(); ++i)
 
  221       common_root_ = parent_model->getCommonRoot(joint_roots_[i], common_root_);
 
  225   for (
const JointModel* joint_root : joint_roots_)
 
  227     const std::vector<const LinkModel*>& links = joint_root->getDescendantLinkModels();
 
  228     updated_link_model_set_.insert(links.begin(), links.end());
 
  230   for (
const LinkModel* updated_link_model : updated_link_model_set_)
 
  232     updated_link_model_name_set_.insert(updated_link_model->getName());
 
  233     updated_link_model_vector_.push_back(updated_link_model);
 
  234     if (!updated_link_model->getShapes().empty())
 
  236       updated_link_model_with_geometry_vector_.push_back(updated_link_model);
 
  237       updated_link_model_with_geometry_set_.insert(updated_link_model);
 
  238       updated_link_model_with_geometry_name_set_.insert(updated_link_model->getName());
 
  241   std::sort(updated_link_model_vector_.begin(), updated_link_model_vector_.end(), OrderLinksByIndex());
 
  242   std::sort(updated_link_model_with_geometry_vector_.begin(), updated_link_model_with_geometry_vector_.end(),
 
  243             OrderLinksByIndex());
 
  244   for (
const LinkModel* updated_link_model : updated_link_model_vector_)
 
  245     updated_link_model_name_vector_.push_back(updated_link_model->getName());
 
  246   for (
const LinkModel* updated_link_model_with_geometry : updated_link_model_with_geometry_vector_)
 
  247     updated_link_model_with_geometry_name_vector_.push_back(updated_link_model_with_geometry->getName());
 
  250   if (joint_roots_.size() == 1 && !active_joint_model_vector_.empty())
 
  255     for (std::size_t k = joint_model_vector_.size() - 1; k > 0; --k)
 
  256       if (!jointPrecedes(joint_model_vector_[k], joint_model_vector_[k - 1]))
 
  321                                                               *active_joint_bounds[i]);
 
  333                                                                     *active_joint_bounds[i],
 
  341                                                        const std::map<JointModel::JointType, double>& distance_map)
 const 
  347     std::map<JointModel::JointType, double>::const_iterator iter =
 
  349     if (iter != distance_map.end())
 
  354                                                                     *active_joint_bounds[i],
 
  363                                                        const std::vector<double>& distances)
 const 
  367     throw Exception(
"When sampling random values nearby for group '" + 
name_ + 
"', distances vector should be of size " +
 
  369                     boost::lexical_cast<std::string>(distances.size()));
 
  372                                                                     *active_joint_bounds[i],
 
  384                                                                 *active_joint_bounds[i], margin))
 
  395                                                              *active_joint_bounds[i]))
 
  404   double max_distance = 0.0;
 
  437     values[mimic_update.dest] = 
values[mimic_update.src] * mimic_update.factor + mimic_update.offset;
 
  448   std::map<std::string, std::map<std::string, double> >::const_iterator it = 
default_states_.find(
name);
 
  489   std::vector<const LinkModel*> tip_links;
 
  495   for (
const LinkModel* link_model : tip_links)
 
  496     tips.push_back(link_model->getName());
 
  520     const auto insert_it = std::lower_bound(tips.cbegin(), tips.cend(), eef_link);
 
  521     if (insert_it == tips.end() || eef_link != *insert_it)  
 
  522       tips.insert(insert_it, eef_link);
 
  529   std::vector<const LinkModel*> tips;
 
  531   if (tips.size() == 1)
 
  533   else if (tips.size() > 1)
 
  535                              "so cannot return only one");
 
  557   for (std::pair<const JointModelGroup* const, KinematicsSolver>& it : 
group_kinematics_.second)
 
  558     it.second.default_ik_timeout_ = ik_timeout;
 
  562                                               std::vector<unsigned int>& joint_bijection)
 const 
  564   joint_bijection.clear();
 
  565   for (
const std::string& ik_jname : ik_jnames)
 
  574                       "IK solver computes joint values for joint '%s' " 
  575                       "but group '%s' does not contain such a joint.",
 
  576                       ik_jname.c_str(), 
getName().c_str());
 
  581       joint_bijection.push_back(it->second + k);
 
  602     for (
const std::pair<const JointModelGroup* const, SolverAllocatorFn>& it : solvers.second)
 
  603       if (it.first->getSolverInstance())
 
  606         ks.allocator_ = it.second;
 
  620   if (!solver || tip.empty())
 
  623   const std::vector<std::string>& tip_frames = solver->getTipFrames();
 
  625   if (tip_frames.empty())
 
  632   for (
const std::string& tip_frame : tip_frames)
 
  635     const std::string& tip_local = tip[0] == 
'/' ? tip.substr(1) : tip;
 
  636     const std::string& tip_frame_local = tip_frame[0] == 
'/' ? tip_frame.substr(1) : tip_frame;
 
  638                     tip_frame_local.c_str());
 
  641     if (tip_local != tip_frame_local)
 
  649         for (
const std::pair<const LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
 
  651           if (fixed_link.first->getName() == tip_local)
 
  667   out << 
"  * Joints:" << std::endl;
 
  669     out << 
"    '" << joint_model->getName() << 
"' (" << joint_model->getTypeName() << 
")" << std::endl;
 
  670   out << 
"  * Variables:" << std::endl;
 
  675     out << 
"    '" << variable_name << 
"', index " 
  676         << (jm->getFirstVariableIndex() + jm->getLocalVariableIndex(variable_name)) << 
" in full state, index " 
  677         << local_idx << 
" in group state";
 
  683   out << 
"  * Variables Index List:" << std::endl;
 
  686     out << variable_index << 
" ";
 
  688     out << 
"(contiguous)";
 
  690     out << 
"(non-contiguous)";
 
  694     out << 
"  * Kinematics solver bijection:" << std::endl;
 
  702     out << 
"  * Compound kinematics solver:" << std::endl;
 
  703     for (
const std::pair<const JointModelGroup* const, KinematicsSolver>& it : 
group_kinematics_.second)
 
  705       out << 
"    " << it.first->getName() << 
":";
 
  706       for (
unsigned int index : it.second.bijection_)
 
  714     out << 
"  * Local Mimic Updates:" << std::endl;
 
  716       out << 
"    [" << mimic_update.dest << 
"] = " << mimic_update.factor << 
" * [" << mimic_update.src << 
"] + " 
  717           << mimic_update.offset << std::endl;
 
  723                                           const std::vector<double>& to_joint_pose, 
double dt)
 const 
  726   if (from_joint_pose.size() != to_joint_pose.size())
 
  732   return isValidVelocityMove(&from_joint_pose[0], &to_joint_pose[0], from_joint_pose.size(), dt);
 
  736                                           std::size_t array_size, 
double dt)
 const 
  741   for (std::size_t i = 0; i < array_size; ++i)
 
  743     double dtheta = std::abs(from_joint_pose[i] - to_joint_pose[i]);
 
  744     const std::vector<moveit::core::VariableBounds>* var_bounds = bounds[bij[i]];
 
  746     if (var_bounds->size() != 1)
 
  749       ROS_ERROR_NAMED(
LOGNAME, 
"Attempting to check velocity bounds for waypoint move with joints that have multiple " 
  753     const double max_velocity = (*var_bounds)[0].max_velocity_;
 
  755     double max_dtheta = dt * max_velocity;
 
  756     if (dtheta > max_dtheta)