40 #include <boost/math/constants/constants.hpp>
46 #include "order_robot_model_items.inc"
52 const std::string
LOGNAME =
"robot_model";
94 if (urdf_model.getRoot())
96 const urdf::Link* root_link_ptr = urdf_model.getRoot().get();
129 typedef std::map<const JointModel*, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
130 std::set<const JointModel*, OrderJointsByIndex>>>
133 void computeDescendantsHelper(
const JointModel* joint, std::vector<const JointModel*>& parents,
134 std::set<const JointModel*>& seen, DescMap& descendants)
138 if (seen.find(joint) != seen.end())
143 descendants[parent].second.insert(joint);
150 descendants[parent].first.insert(lm);
151 descendants[joint].first.insert(lm);
153 parents.push_back(joint);
155 for (
const JointModel* child_joint_model : ch)
156 computeDescendantsHelper(child_joint_model, parents, seen, descendants);
158 for (
const JointModel* mimic_joint_model : mim)
159 computeDescendantsHelper(mimic_joint_model, parents, seen, descendants);
163 void computeCommonRootsHelper(
const JointModel* joint, std::vector<int>& common_roots,
int size)
172 for (std::size_t i = 0; i < ch.size(); ++i)
174 const std::vector<const JointModel*>& a = ch[i]->getDescendantJointModels();
175 for (std::size_t j = i + 1; j < ch.size(); ++j)
177 const std::vector<const JointModel*>& b = ch[j]->getDescendantJointModels();
179 common_roots[ch[i]->getJointIndex() * size + m->getJointIndex()] =
180 common_roots[ch[i]->getJointIndex() + m->getJointIndex() * size] = joint->
getJointIndex();
183 common_roots[k->getJointIndex() * size + ch[j]->getJointIndex()] =
184 common_roots[k->getJointIndex() + ch[j]->getJointIndex() * size] = joint->
getJointIndex();
186 common_roots[k->getJointIndex() * size + m->getJointIndex()] =
187 common_roots[k->getJointIndex() + m->getJointIndex() * size] = joint->
getJointIndex();
190 computeCommonRootsHelper(ch[i], common_roots, size);
217 const std::vector<const JointModel*>&
d = joint_model->getDescendantJointModels();
218 for (
const JointModel* descendant_joint_model : d)
220 joint_model->getJointIndex()] =
229 std::vector<const JointModel*> parents;
230 std::set<const JointModel*> seen;
233 computeDescendantsHelper(
root_joint_, parents, seen, descendants);
234 for (std::pair<
const JointModel*
const, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
235 std::set<const JointModel*, OrderJointsByIndex>>>& descendant :
238 JointModel* jm =
const_cast<JointModel*
>(descendant.first);
239 for (
const JointModel* jt : descendant.second.second)
240 jm->addDescendantJointModel(jt);
241 for (
const LinkModel* jt : descendant.second.first)
242 jm->addDescendantLinkModel(jt);
263 if (!name_order.empty())
265 for (std::size_t j = 0; j < name_order.size(); ++j)
299 if (link_considered[link->getLinkIndex()])
304 for (
auto& tf_base : associated_transforms)
306 link_considered[tf_base.first->getLinkIndex()] =
true;
307 for (
auto& tf_target : associated_transforms)
309 if (&tf_base != &tf_target)
310 const_cast<LinkModel*
>(tf_base.first)
311 ->addAssociatedFixedTransform(tf_target.first, tf_base.second.inverse() * tf_target.second);
323 const std::vector<srdf::Model::GroupState>& ds = srdf_model.
getGroupStates();
329 std::vector<const JointModel*> remaining_joints = jmg->getActiveJointModels();
330 std::map<std::string, double> state;
331 for (std::map<std::string, std::vector<double>>::const_iterator jt = group_state.joint_values_.begin();
332 jt != group_state.joint_values_.end(); ++jt)
334 if (jmg->hasJointModel(jt->first))
336 const JointModel* jm = jmg->getJointModel(jt->first);
337 const std::vector<std::string>& vn = jm->getVariableNames();
339 auto it_found = std::find(remaining_joints.begin(), remaining_joints.end(), jm);
340 if (it_found != remaining_joints.end())
341 remaining_joints.erase(it_found);
342 if (vn.size() == jt->second.size())
343 for (std::size_t j = 0; j < vn.size(); ++j)
344 state[vn[j]] = jt->second[j];
347 "The model for joint '%s' requires %d variable values, "
348 "but only %d variable values were supplied in default state '%s' for group '%s'",
349 jt->first.c_str(), (
int)vn.size(), (
int)jt->second.size(), group_state.name_.c_str(),
350 jmg->getName().c_str());
354 "Group state '%s' specifies value for joint '%s', "
355 "but that joint is not part of group '%s'",
356 group_state.name_.c_str(), jt->first.c_str(), jmg->getName().c_str());
358 if (!remaining_joints.empty())
360 std::stringstream missing;
361 missing << (*remaining_joints.begin())->
getName();
362 for (
auto j = ++remaining_joints.begin(); j != remaining_joints.end(); j++)
364 missing <<
", " << (*j)->getName();
367 <<
"' doesn't specify all group joints in group '"
368 << group_state.group_ <<
"'. " << missing.str() <<
" "
369 << (remaining_joints.size() > 1 ?
"are" :
"is") <<
" missing.");
372 jmg->addDefaultState(group_state.name_, state);
376 group_state.name_.c_str(), group_state.group_.c_str());
385 const urdf::Joint* jm = urdf_model.getJoint(joint_model->getName()).get();
389 JointModelMap::const_iterator jit =
joint_model_map_.find(jm->mimic->joint_name);
392 if (joint_model->getVariableCount() == jit->second->getVariableCount())
393 joint_model->setMimic(jit->second, jm->mimic->multiplier, jm->mimic->offset);
396 joint_model->getName().c_str(), jm->mimic->joint_name.c_str());
400 jm->mimic->joint_name.c_str());
410 if (joint_model->getMimic())
412 if (joint_model->getMimic()->getMimic())
414 joint_model->setMimic(joint_model->getMimic()->getMimic(),
415 joint_model->getMimicFactor() * joint_model->getMimic()->getMimicFactor(),
416 joint_model->getMimicOffset() +
417 joint_model->getMimicFactor() * joint_model->getMimic()->getMimicOffset());
420 if (joint_model == joint_model->getMimic())
424 joint_model_recal->setMimic(
nullptr, 0.0, 0.0);
432 if (joint_model->getMimic())
434 const_cast<JointModel*
>(joint_model->getMimic())->addMimicRequest(joint_model);
501 const std::vector<srdf::Model::Group>& group_configs = srdf_model.
getGroups();
504 std::vector<bool> processed(group_configs.size(),
false);
512 for (std::size_t i = 0; i < group_configs.size(); ++i)
516 bool all_subgroups_added =
true;
517 for (
const std::string& subgroup : group_configs[i].subgroups_)
520 all_subgroups_added =
false;
523 if (all_subgroups_added)
533 for (std::size_t i = 0; i < processed.size(); ++i)
536 group_configs[i].
name_.c_str());
557 std::vector<std::string> subgroup_names;
561 if (jt->first != it->first)
566 for (
const JointModel* sub_joint : sub_joints)
567 if (joints.find(sub_joint) == joints.end())
573 subgroup_names.push_back(sub_jmg->
getName());
575 if (!subgroup_names.empty())
583 const std::vector<srdf::Model::EndEffector>& eefs = srdf_model.
getEndEffectors();
588 if (eef.component_group_ == it->first)
591 it->second->setEndEffectorName(eef.name_);
597 std::vector<JointModelGroup*> possible_parent_groups;
600 if (jt->first != it->first)
602 if (jt->second->hasLinkModel(eef.parent_link_))
604 jt->second->attachEndEffector(eef.name_);
605 possible_parent_groups.push_back(jt->second);
609 JointModelGroup* eef_parent_group =
nullptr;
611 if (!eef.parent_group_.empty())
616 if (jt->second->hasLinkModel(eef.parent_link_))
618 if (jt->second != it->second)
619 eef_parent_group = jt->second;
622 eef.parent_group_.c_str(), eef.name_.c_str());
626 "Group '%s' was specified as parent group for end-effector '%s' "
627 "but it does not include the parent link '%s'",
628 eef.parent_group_.c_str(), eef.name_.c_str(), eef.parent_link_.c_str());
632 eef.parent_group_.c_str(), eef.name_.c_str());
636 if (eef_parent_group ==
nullptr)
637 if (!possible_parent_groups.empty())
641 std::size_t best = 0;
642 for (std::size_t g = 1; g < possible_parent_groups.size(); ++g)
646 eef_parent_group = possible_parent_groups[best];
649 if (eef_parent_group)
651 it->second->setEndEffectorParent(eef_parent_group->getName(), eef.parent_link_);
656 it->second->setEndEffectorParent(
"", eef.parent_link_);
671 std::set<const JointModel*> jset;
674 for (
const std::pair<std::string, std::string>& chain : gc.
chains_)
678 if (base_link && tip_link)
681 const LinkModel* lm = tip_link;
682 std::vector<const JointModel*> cj;
687 cj.push_back(lm->getParentJointModel());
696 std::size_t
index = 0;
697 std::vector<const JointModel*> cj2;
700 for (std::size_t j = 0; j < cj.size(); ++j)
701 if (cj[j] == lm->getParentJointModel())
708 cj2.push_back(lm->getParentJointModel());
709 lm = lm->getParentJointModel()->getParentLinkModel();
713 jset.insert(cj.begin(), cj.begin() + index);
714 jset.insert(cj2.begin(), cj2.end());
719 jset.insert(cj.begin(), cj.end());
724 for (
const std::string& joint : gc.
joints_)
732 for (
const std::string& link : gc.
links_)
740 for (
const std::string& subgroup : gc.
subgroups_)
746 const std::vector<const JointModel*>& js = sg->getJointModels();
747 for (
const JointModel* j : js)
751 const std::vector<const JointModel*>& fs = sg->getFixedJointModels();
752 for (
const JointModel* f : fs)
756 const std::vector<const JointModel*>& ms = sg->getMimicJointModels();
757 for (
const JointModel* m : ms)
768 std::vector<const JointModel*> joints;
769 joints.reserve(jset.size());
770 for (
const JointModel* it : jset)
771 joints.push_back(it);
773 JointModelGroup* jmg =
new JointModelGroup(gc.
name_, gc, joints,
this);
782 JointModel* joint = urdf_link->parent_joint ?
785 if (joint ==
nullptr)
794 joint->setParentLinkModel(parent);
798 joint->setChildLinkModel(link);
799 link->setParentLinkModel(parent);
807 if (!link->getShapes().empty())
814 link->setParentJointModel(joint);
817 for (
const urdf::LinkSharedPtr& child_link : urdf_link->child_links)
819 JointModel* jm =
buildRecursive(link, child_link.get(), srdf_model);
821 link->addChildJointModel(jm);
829 static inline VariableBounds jointBoundsFromURDF(
const urdf::Joint* urdf_joint)
832 if (urdf_joint->safety)
834 b.position_bounded_ =
true;
835 b.min_position_ = urdf_joint->safety->soft_lower_limit;
836 b.max_position_ = urdf_joint->safety->soft_upper_limit;
837 if (urdf_joint->limits)
839 if (urdf_joint->limits->lower > b.min_position_)
840 b.min_position_ = urdf_joint->limits->lower;
841 if (urdf_joint->limits->upper < b.max_position_)
842 b.max_position_ = urdf_joint->limits->upper;
847 if (urdf_joint->limits)
849 b.position_bounded_ =
true;
850 b.min_position_ = urdf_joint->limits->lower;
851 b.max_position_ = urdf_joint->limits->upper;
854 if (urdf_joint->limits)
856 b.max_velocity_ = fabs(urdf_joint->limits->velocity);
857 b.min_velocity_ = -b.max_velocity_;
858 b.velocity_bounded_ = b.max_velocity_ > std::numeric_limits<double>::epsilon();
867 JointModel* new_joint_model =
nullptr;
872 switch (urdf_joint->type)
874 case urdf::Joint::REVOLUTE:
876 RevoluteJointModel* j =
new RevoluteJointModel(urdf_joint->name);
877 j->setVariableBounds(j->getName(), jointBoundsFromURDF(urdf_joint));
878 j->setContinuous(
false);
879 j->setAxis(
Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z));
883 case urdf::Joint::CONTINUOUS:
885 RevoluteJointModel* j =
new RevoluteJointModel(urdf_joint->name);
886 j->setVariableBounds(j->getName(), jointBoundsFromURDF(urdf_joint));
887 j->setContinuous(
true);
888 j->setAxis(
Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z));
892 case urdf::Joint::PRISMATIC:
894 PrismaticJointModel* j =
new PrismaticJointModel(urdf_joint->name);
895 j->setVariableBounds(j->getName(), jointBoundsFromURDF(urdf_joint));
896 j->setAxis(
Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z));
900 case urdf::Joint::FLOATING:
901 new_joint_model =
new FloatingJointModel(urdf_joint->name);
903 case urdf::Joint::PLANAR:
904 new_joint_model =
new PlanarJointModel(urdf_joint->name);
906 case urdf::Joint::FIXED:
907 new_joint_model =
new FixedJointModel(urdf_joint->name);
916 const std::vector<srdf::Model::VirtualJoint>& virtual_joints = srdf_model.
getVirtualJoints();
919 if (virtual_joint.child_link_ != child_link->name)
922 "Skipping virtual joint '%s' because its child frame '%s' "
923 "does not match the URDF frame '%s'",
924 virtual_joint.name_.c_str(), virtual_joint.child_link_.c_str(), child_link->name.c_str());
926 else if (virtual_joint.parent_frame_.empty())
929 virtual_joint.name_.c_str());
933 if (virtual_joint.type_ ==
"fixed")
935 else if (virtual_joint.type_ ==
"planar")
937 else if (virtual_joint.type_ ==
"floating")
942 if (virtual_joint.type_ !=
"fixed")
950 if (!new_joint_model)
953 new_joint_model =
new FixedJointModel(
"ASSUMED_FIXED_ROOT_JOINT");
959 new_joint_model->setDistanceFactor(new_joint_model->getStateSpaceDimension());
960 const std::vector<srdf::Model::PassiveJoint>& pjoints = srdf_model.
getPassiveJoints();
963 if (new_joint_model->getName() == pjoint.name_)
965 new_joint_model->setPassive(
true);
971 return new_joint_model;
976 static inline Eigen::Isometry3d urdfPose2Isometry3d(
const urdf::Pose& pose)
978 Eigen::Quaterniond q(pose.rotation.w, pose.rotation.x, pose.rotation.y, pose.rotation.z);
979 Eigen::Isometry3d af(Eigen::Translation3d(pose.position.x, pose.position.y, pose.position.z) * q);
986 LinkModel* new_link_model =
new LinkModel(urdf_link->name);
988 const std::vector<urdf::CollisionSharedPtr>& col_array =
989 urdf_link->collision_array.empty() ? std::vector<urdf::CollisionSharedPtr>(1, urdf_link->collision) :
990 urdf_link->collision_array;
992 std::vector<shapes::ShapeConstPtr>
shapes;
993 EigenSTL::vector_Isometry3d poses;
995 for (
const urdf::CollisionSharedPtr& col : col_array)
997 if (col && col->geometry)
1003 poses.push_back(urdfPose2Isometry3d(col->origin));
1009 bool warn_about_missing_collision =
false;
1012 const auto& vis_array = urdf_link->visual_array.empty() ? std::vector<urdf::VisualSharedPtr>{ urdf_link->visual } :
1013 urdf_link->visual_array;
1014 for (
const urdf::VisualSharedPtr& vis : vis_array)
1016 if (vis && vis->geometry)
1017 warn_about_missing_collision =
true;
1020 if (warn_about_missing_collision)
1023 "Link " << urdf_link->name
1024 <<
" has visual geometry but no collision geometry. "
1025 "Collision geometry will be left empty. "
1026 "Fix your URDF file by explicitly specifying collision geometry.");
1029 new_link_model->setGeometry(
shapes, poses);
1032 if (urdf_link->visual && urdf_link->visual->geometry)
1034 if (urdf_link->visual->geometry->type == urdf::Geometry::MESH)
1036 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(urdf_link->visual->geometry.get());
1037 if (!mesh->filename.empty())
1038 new_link_model->setVisualMesh(mesh->filename, urdfPose2Isometry3d(urdf_link->visual->origin),
1042 else if (urdf_link->collision && urdf_link->collision->geometry)
1044 if (urdf_link->collision->geometry->type == urdf::Geometry::MESH)
1046 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(urdf_link->collision->geometry.get());
1047 if (!mesh->filename.empty())
1048 new_link_model->setVisualMesh(mesh->filename, urdfPose2Isometry3d(urdf_link->collision->origin),
1053 if (urdf_link->parent_joint)
1054 new_link_model->setJointOriginTransform(
1055 urdfPose2Isometry3d(urdf_link->parent_joint->parent_to_joint_origin_transform));
1057 return new_link_model;
1067 case urdf::Geometry::SPHERE:
1068 new_shape =
new shapes::Sphere(
static_cast<const urdf::Sphere*
>(geom)->radius);
1070 case urdf::Geometry::BOX:
1072 urdf::Vector3 dim =
static_cast<const urdf::Box*
>(geom)->dim;
1076 case urdf::Geometry::CYLINDER:
1077 new_shape =
new shapes::Cylinder(
static_cast<const urdf::Cylinder*
>(geom)->radius,
1078 static_cast<const urdf::Cylinder*
>(geom)->length);
1080 case urdf::Geometry::MESH:
1082 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(geom);
1083 if (!mesh->filename.empty())
1189 int src = mimic_joint->getMimic()->getFirstVariableIndex();
1190 int dest = mimic_joint->getFirstVariableIndex();
1191 values[dest] =
values[src] * mimic_joint->getMimicFactor() + mimic_joint->getMimicOffset();
1203 std::map<std::string, double>& values)
const
1229 std::vector<std::string>& missing_variables)
const
1231 missing_variables.clear();
1232 std::set<std::string> keys(variables.begin(), variables.end());
1234 if (keys.find(variable_name) == keys.end())
1236 missing_variables.push_back(variable_name);
1249 double max_distance = 0.0;
1253 return max_distance;
1257 double margin)
const
1262 *active_joint_bounds[i], margin))
1270 bool change =
false;
1273 *active_joint_bounds[i]))
1306 std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->
getName());
1307 if (jt != allocators.end())
1309 std::pair<SolverAllocatorFn, SolverAllocatorMapFn> solver_allocator_pair;
1310 solver_allocator_pair.first = jt->second;
1319 std::pair<SolverAllocatorFn, SolverAllocatorMapFn> solver_allocator_pair;
1320 std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->
getName());
1321 if (jt == allocators.end())
1324 std::set<const JointModel*> joints;
1327 std::vector<const JointModelGroup*> subs;
1330 for (
const std::pair<const std::string, SolverAllocatorFn>& allocator : allocators)
1338 std::set<const JointModel*> sub_joints;
1341 if (std::includes(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end()))
1343 std::set<const JointModel*> joint_model_set;
1344 std::set_difference(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end(),
1345 std::inserter(joint_model_set, joint_model_set.end()));
1351 subs.push_back(sub);
1352 joints.swap(joint_model_set);
1359 std::stringstream ss;
1363 solver_allocator_pair.second[sub] = allocators.find(sub->
getName())->second;
1378 std::ios_base::fmtflags old_flags = out.flags();
1379 out.setf(std::ios::fixed, std::ios::floatfield);
1380 std::streamsize old_prec = out.precision();
1382 out <<
"Joints: " << std::endl;
1385 out <<
" '" << joint_model->getName() <<
"' (" << joint_model->getTypeName() <<
")" << std::endl;
1386 out <<
" * Joint Index: " << joint_model->getJointIndex() << std::endl;
1387 const std::vector<std::string>& vn = joint_model->getVariableNames();
1388 out <<
" * " << vn.size() << (vn.size() > 1 ?
" variables:" : (vn.empty() ?
" variables" :
" variable:"))
1390 int idx = joint_model->getFirstVariableIndex();
1391 for (
const std::string& it : vn)
1393 out <<
" * '" << it <<
"', index " << idx++ <<
" in full state";
1394 if (joint_model->getMimic())
1395 out <<
", mimic '" << joint_model->getMimic()->getName() <<
"'";
1396 if (joint_model->isPassive())
1399 out <<
" " << joint_model->getVariableBounds(it) << std::endl;
1403 out.precision(old_prec);
1404 out.flags(old_flags);
1405 out <<
"Links: " << std::endl;
1408 out <<
" '" << link_model->getName() <<
"' with " << link_model->getShapes().size() <<
" geoms" << std::endl;
1409 if (link_model->parentJointIsFixed())
1411 <<
"parent joint is fixed" << std::endl;
1412 if (link_model->jointOriginTransformIsIdentity())
1414 <<
"joint origin transform is identity" << std::endl;
1417 out <<
"Available groups: " << std::endl;
1419 joint_model_group->printGroupInfo(out);
1425 associated_transforms[link] =
transform * link->getJointOriginTransform();
1426 for (std::size_t i = 0; i < link->getChildJointModels().size(); ++i)
1429 transform * link->getJointOriginTransform(), associated_transforms);