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 , is_contiguous_index_list_(true)
110 , is_single_dof_(true)
114 joint_model_vector_ = unsorted_group_joints;
115 std::sort(joint_model_vector_.begin(), joint_model_vector_.end(), OrderJointsByIndex());
116 joint_model_name_vector_.reserve(joint_model_vector_.size());
120 for (
const JointModel* joint_model : joint_model_vector_)
122 joint_model_name_vector_.push_back(joint_model->getName());
123 joint_model_map_[joint_model->getName()] = joint_model;
124 unsigned int vc = joint_model->getVariableCount();
128 is_single_dof_ =
false;
129 const std::vector<std::string>& name_order = joint_model->getVariableNames();
130 if (joint_model->getMimic() ==
nullptr)
132 active_joint_model_vector_.push_back(joint_model);
133 active_joint_model_name_vector_.push_back(joint_model->getName());
134 active_joint_model_start_index_.push_back(variable_count_);
135 active_joint_models_bounds_.push_back(&joint_model->getVariableBounds());
138 mimic_joints_.push_back(joint_model);
139 for (
const std::string& name : name_order)
142 variable_names_set_.insert(name);
145 int first_index = joint_model->getFirstVariableIndex();
146 for (std::size_t j = 0; j < name_order.size(); ++j)
148 variable_index_list_.push_back(first_index + j);
149 joint_variables_index_map_[name_order[j]] = variable_count_ + j;
151 joint_variables_index_map_[joint_model->getName()] = variable_count_;
154 static_cast<const RevoluteJointModel*
>(joint_model)->isContinuous())
155 continuous_joint_model_vector_.push_back(joint_model);
157 variable_count_ += vc;
160 fixed_joints_.push_back(joint_model);
165 for (
const JointModel* active_joint_model : active_joint_model_vector_)
168 if (!includesParent(active_joint_model,
this))
169 joint_roots_.push_back(active_joint_model);
174 if (variable_index_list_.empty())
175 is_contiguous_index_list_ =
false;
177 for (std::size_t i = 1; i < variable_index_list_.size(); ++i)
178 if (variable_index_list_[i] != variable_index_list_[i - 1] + 1)
180 is_contiguous_index_list_ =
false;
185 for (
const JointModel* mimic_joint : mimic_joints_)
187 if (hasJointModel(mimic_joint->getMimic()->getName()))
189 int src = joint_variables_index_map_[mimic_joint->getMimic()->getName()];
190 int dest = joint_variables_index_map_[mimic_joint->getName()];
191 GroupMimicUpdate mu(src, dest, mimic_joint->getMimicFactor(), mimic_joint->getMimicOffset());
192 group_mimic_update_.push_back(mu);
196 std::set<const LinkModel*> group_links_set;
197 for (
const JointModel* joint_model : joint_model_vector_)
198 group_links_set.insert(joint_model->getChildLinkModel());
199 for (
const LinkModel* group_link : group_links_set)
200 link_model_vector_.push_back(group_link);
201 std::sort(link_model_vector_.begin(), link_model_vector_.end(), OrderLinksByIndex());
203 for (
const LinkModel* link_model : link_model_vector_)
205 link_model_map_[link_model->getName()] = link_model;
206 link_model_name_vector_.push_back(link_model->getName());
207 if (!link_model->getShapes().empty())
209 link_model_with_geometry_vector_.push_back(link_model);
210 link_model_with_geometry_name_vector_.push_back(link_model->getName());
215 if (!joint_roots_.empty())
217 common_root_ = joint_roots_[0];
218 for (std::size_t i = 1; i < joint_roots_.size(); ++i)
219 common_root_ = parent_model->getCommonRoot(joint_roots_[i], common_root_);
223 for (
const JointModel* joint_root : joint_roots_)
225 const std::vector<const LinkModel*>& links = joint_root->getDescendantLinkModels();
226 updated_link_model_set_.insert(links.begin(), links.end());
228 for (
const LinkModel* updated_link_model : updated_link_model_set_)
230 updated_link_model_name_set_.insert(updated_link_model->getName());
231 updated_link_model_vector_.push_back(updated_link_model);
232 if (!updated_link_model->getShapes().empty())
234 updated_link_model_with_geometry_vector_.push_back(updated_link_model);
235 updated_link_model_with_geometry_set_.insert(updated_link_model);
236 updated_link_model_with_geometry_name_set_.insert(updated_link_model->getName());
239 std::sort(updated_link_model_vector_.begin(), updated_link_model_vector_.end(), OrderLinksByIndex());
240 std::sort(updated_link_model_with_geometry_vector_.begin(), updated_link_model_with_geometry_vector_.end(),
241 OrderLinksByIndex());
242 for (
const LinkModel* updated_link_model : updated_link_model_vector_)
243 updated_link_model_name_vector_.push_back(updated_link_model->getName());
244 for (
const LinkModel* updated_link_model_with_geometry : updated_link_model_with_geometry_vector_)
245 updated_link_model_with_geometry_name_vector_.push_back(updated_link_model_with_geometry->getName());
248 if (joint_roots_.size() == 1 && !active_joint_model_vector_.empty())
253 for (std::size_t k = joint_model_vector_.size() - 1; k > 0; --k)
254 if (!jointPrecedes(joint_model_vector_[k], joint_model_vector_[k - 1]))
319 *active_joint_bounds[i]);
331 *active_joint_bounds[i],
339 const std::map<JointModel::JointType, double>& distance_map)
const
345 std::map<JointModel::JointType, double>::const_iterator iter =
347 if (iter != distance_map.end())
352 *active_joint_bounds[i],
361 const std::vector<double>& distances)
const
365 throw Exception(
"When sampling random values nearby for group '" +
name_ +
"', distances vector should be of size " +
367 boost::lexical_cast<std::string>(distances.size()));
370 *active_joint_bounds[i],
382 *active_joint_bounds[i], margin))
393 *active_joint_bounds[i]))
402 double max_distance = 0.0;
435 values[mimic_update.dest] =
values[mimic_update.src] * mimic_update.factor + mimic_update.offset;
446 std::map<std::string, std::map<std::string, double> >::const_iterator it =
default_states_.find(
name);
487 std::vector<const LinkModel*> tip_links;
493 for (
const LinkModel* link_model : tip_links)
494 tips.push_back(link_model->getName());
518 const auto insert_it = std::lower_bound(tips.cbegin(), tips.cend(), eef_link);
519 if (insert_it == tips.end() || eef_link != *insert_it)
520 tips.insert(insert_it, eef_link);
527 std::vector<const LinkModel*> tips;
529 if (tips.size() == 1)
531 else if (tips.size() > 1)
533 "so cannot return only one");
555 for (std::pair<const JointModelGroup* const, KinematicsSolver>& it :
group_kinematics_.second)
556 it.second.default_ik_timeout_ = ik_timeout;
560 std::vector<unsigned int>& joint_bijection)
const
562 joint_bijection.clear();
563 for (
const std::string& ik_jname : ik_jnames)
572 "IK solver computes joint values for joint '%s' "
573 "but group '%s' does not contain such a joint.",
574 ik_jname.c_str(),
getName().c_str());
579 joint_bijection.push_back(it->second + k);
600 for (
const std::pair<const JointModelGroup* const, SolverAllocatorFn>& it : solvers.second)
601 if (it.first->getSolverInstance())
604 ks.allocator_ = it.second;
618 if (!solver || tip.empty())
621 const std::vector<std::string>& tip_frames = solver->getTipFrames();
623 if (tip_frames.empty())
630 for (
const std::string& tip_frame : tip_frames)
633 const std::string& tip_local = tip[0] ==
'/' ? tip.substr(1) : tip;
634 const std::string& tip_frame_local = tip_frame[0] ==
'/' ? tip_frame.substr(1) : tip_frame;
636 tip_frame_local.c_str());
639 if (tip_local != tip_frame_local)
647 for (
const std::pair<const LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
649 if (fixed_link.first->getName() == tip_local)
665 out <<
" * Joints:" << std::endl;
667 out <<
" '" << joint_model->getName() <<
"' (" << joint_model->getTypeName() <<
")" << std::endl;
668 out <<
" * Variables:" << std::endl;
673 out <<
" '" << variable_name <<
"', index "
674 << (jm->getFirstVariableIndex() + jm->getLocalVariableIndex(variable_name)) <<
" in full state, index "
675 << local_idx <<
" in group state";
681 out <<
" * Variables Index List:" << std::endl;
684 out << variable_index <<
" ";
686 out <<
"(contiguous)";
688 out <<
"(non-contiguous)";
692 out <<
" * Kinematics solver bijection:" << std::endl;
700 out <<
" * Compound kinematics solver:" << std::endl;
701 for (
const std::pair<const JointModelGroup* const, KinematicsSolver>& it :
group_kinematics_.second)
703 out <<
" " << it.first->getName() <<
":";
704 for (
unsigned int index : it.second.bijection_)
712 out <<
" * Local Mimic Updates:" << std::endl;
714 out <<
" [" << mimic_update.dest <<
"] = " << mimic_update.factor <<
" * [" << mimic_update.src <<
"] + "
715 << mimic_update.offset << std::endl;
721 const std::vector<double>& to_joint_pose,
double dt)
const
724 if (from_joint_pose.size() != to_joint_pose.size())
730 return isValidVelocityMove(&from_joint_pose[0], &to_joint_pose[0], from_joint_pose.size(), dt);
734 std::size_t array_size,
double dt)
const
739 for (std::size_t i = 0; i < array_size; ++i)
741 double dtheta = std::abs(from_joint_pose[i] - to_joint_pose[i]);
742 const std::vector<moveit::core::VariableBounds>* var_bounds = bounds[bij[i]];
744 if (var_bounds->size() != 1)
747 ROS_ERROR_NAMED(
LOGNAME,
"Attempting to check velocity bounds for waypoint move with joints that have multiple "
751 const double max_velocity = (*var_bounds)[0].max_velocity_;
753 double max_dtheta = dt * max_velocity;
754 if (dtheta > max_dtheta)