39 #include <geometric_shapes/shape_operations.h>
40 #include <rclcpp/logger.hpp>
52 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_robot_model.robot_model");
59 buildModel(*urdf_model, *srdf_model);
82 void RobotModel::buildModel(
const urdf::ModelInterface& urdf_model,
const srdf::Model& srdf_model)
89 RCLCPP_INFO(LOGGER,
"Loading robot model '%s'...",
model_name_.c_str());
91 if (urdf_model.getRoot())
93 const urdf::Link* root_link_ptr = urdf_model.getRoot().get();
96 RCLCPP_DEBUG(LOGGER,
"... building kinematic chain");
97 root_joint_ = buildRecursive(
nullptr, root_link_ptr, srdf_model);
100 RCLCPP_DEBUG(LOGGER,
"... building mimic joints");
101 buildMimic(urdf_model);
103 RCLCPP_DEBUG(LOGGER,
"... computing joint indexing");
108 RCLCPP_WARN(LOGGER,
"No geometry is associated to any robot links");
113 RCLCPP_DEBUG(LOGGER,
"... constructing joint groups");
114 buildGroups(srdf_model);
116 RCLCPP_DEBUG(LOGGER,
"... constructing joint group states");
117 buildGroupStates(srdf_model);
124 RCLCPP_WARN(LOGGER,
"No root link found");
130 typedef std::map<const JointModel*, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
131 std::set<const JointModel*, OrderJointsByIndex>>>
134 void computeDescendantsHelper(
const JointModel* joint, std::vector<const JointModel*>& parents,
135 std::set<const JointModel*>& seen, DescMap& descendants)
139 if (seen.find(joint) != seen.end())
143 for (
const JointModel* parent : parents)
144 descendants[parent].second.insert(joint);
146 const LinkModel* lm = joint->getChildLinkModel();
150 for (
const JointModel* parent : parents)
151 descendants[parent].first.insert(lm);
152 descendants[joint].first.insert(lm);
154 parents.push_back(joint);
155 const std::vector<const JointModel*>& ch = lm->getChildJointModels();
156 for (
const JointModel* child_joint_model : ch)
157 computeDescendantsHelper(child_joint_model, parents, seen, descendants);
158 const std::vector<const JointModel*>& mim = joint->getMimicRequests();
159 for (
const JointModel* mimic_joint_model : mim)
160 computeDescendantsHelper(mimic_joint_model, parents, seen, descendants);
164 void computeCommonRootsHelper(
const JointModel* joint, std::vector<int>& common_roots,
int size)
168 const LinkModel* lm = joint->getChildLinkModel();
172 const std::vector<const JointModel*>& ch = lm->getChildJointModels();
173 for (std::size_t i = 0; i < ch.size(); ++i)
175 const std::vector<const JointModel*>& a = ch[i]->getDescendantJointModels();
176 for (std::size_t j = i + 1; j < ch.size(); ++j)
178 const std::vector<const JointModel*>& b = ch[j]->getDescendantJointModels();
179 for (
const JointModel* m : b)
181 common_roots[ch[i]->getJointIndex() * size + m->getJointIndex()] =
182 common_roots[ch[i]->getJointIndex() + m->getJointIndex() * size] = joint->getJointIndex();
184 for (
const JointModel* k : a)
186 common_roots[k->getJointIndex() * size + ch[j]->getJointIndex()] =
187 common_roots[k->getJointIndex() + ch[j]->getJointIndex() * size] = joint->getJointIndex();
188 for (
const JointModel* m : b)
190 common_roots[k->getJointIndex() * size + m->getJointIndex()] =
191 common_roots[k->getJointIndex() + m->getJointIndex() * size] = joint->getJointIndex();
195 computeCommonRootsHelper(ch[i], common_roots, size);
200 void RobotModel::computeCommonRoots()
222 const std::vector<const JointModel*>&
d = joint_model->getDescendantJointModels();
223 for (
const JointModel* descendant_joint_model :
d)
226 joint_model->getJointIndex()] =
233 void RobotModel::computeDescendants()
236 std::vector<const JointModel*> parents;
237 std::set<const JointModel*> seen;
240 computeDescendantsHelper(
root_joint_, parents, seen, descendants);
241 for (std::pair<
const JointModel*
const, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
242 std::set<const JointModel*, OrderJointsByIndex>>>& descendant :
245 JointModel* jm =
const_cast<JointModel*
>(descendant.first);
246 for (
const JointModel* jt : descendant.second.second)
247 jm->addDescendantJointModel(jt);
248 for (
const LinkModel* jt : descendant.second.first)
249 jm->addDescendantLinkModel(jt);
253 void RobotModel::buildJointInfo()
263 const std::vector<std::string>& name_order = joint->getVariableNames();
266 if (!name_order.empty())
268 for (std::size_t j = 0; j < name_order.size(); ++j)
274 if (joint->getMimic() ==
nullptr)
283 if (joint->getType() ==
JointModel::REVOLUTE &&
static_cast<const RevoluteJointModel*
>(joint)->isContinuous())
289 std::size_t vc = joint->getVariableCount();
305 if (link_considered[link->getLinkIndex()])
310 for (
auto& tf_base : associated_transforms)
312 link_considered[tf_base.first->getLinkIndex()] =
true;
313 for (
auto& tf_target : associated_transforms)
315 if (&tf_base != &tf_target)
317 const_cast<LinkModel*
>(tf_base.first)
318 ->addAssociatedFixedTransform(tf_target.first, tf_base.second.inverse() * tf_target.second);
324 computeDescendants();
325 computeCommonRoots();
328 void RobotModel::buildGroupStates(
const srdf::Model& srdf_model)
331 const std::vector<srdf::Model::GroupState>& ds = srdf_model.getGroupStates();
332 for (
const srdf::Model::GroupState& group_state : ds)
337 std::vector<const JointModel*> remaining_joints = jmg->getActiveJointModels();
338 std::map<std::string, double> state;
339 for (std::map<std::string, std::vector<double>>::const_iterator jt = group_state.joint_values_.begin();
340 jt != group_state.joint_values_.end(); ++jt)
342 if (jmg->hasJointModel(jt->first))
344 const JointModel* jm = jmg->getJointModel(jt->first);
345 const std::vector<std::string>& vn = jm->getVariableNames();
347 auto it_found = std::find(remaining_joints.begin(), remaining_joints.end(), jm);
348 if (it_found != remaining_joints.end())
349 remaining_joints.erase(it_found);
350 if (vn.size() == jt->second.size())
352 for (std::size_t j = 0; j < vn.size(); ++j)
353 state[vn[j]] = jt->second[j];
358 "The model for joint '%s' requires %d variable values, "
359 "but only %d variable values were supplied in default state '%s' for group '%s'",
360 jt->first.c_str(),
static_cast<int>(vn.size()),
static_cast<int>(jt->second.size()),
361 group_state.name_.c_str(), jmg->getName().c_str());
367 "Group state '%s' specifies value for joint '%s', "
368 "but that joint is not part of group '%s'",
369 group_state.name_.c_str(), jt->first.c_str(), jmg->getName().c_str());
372 if (!remaining_joints.empty())
374 std::stringstream missing;
375 missing << (*remaining_joints.begin())->
getName();
376 for (
auto j = ++remaining_joints.begin(); j != remaining_joints.end(); ++j)
378 missing <<
", " << (*j)->getName();
380 RCLCPP_WARN_STREAM(LOGGER,
"Group state '" << group_state.name_
381 <<
"' doesn't specify all group joints in group '"
382 << group_state.group_ <<
"'. " << missing.str() <<
' '
383 << (remaining_joints.size() > 1 ?
"are" :
"is") <<
" missing.");
386 jmg->addDefaultState(group_state.name_, state);
390 RCLCPP_ERROR(LOGGER,
"Group state '%s' specified for group '%s', but that group does not exist",
391 group_state.name_.c_str(), group_state.group_.c_str());
396 void RobotModel::buildMimic(
const urdf::ModelInterface& urdf_model)
401 const urdf::Joint* jm = urdf_model.getJoint(joint_model->getName()).get();
406 JointModelMap::const_iterator jit =
joint_model_map_.find(jm->mimic->joint_name);
409 if (joint_model->getVariableCount() == jit->second->getVariableCount())
411 joint_model->setMimic(jit->second, jm->mimic->multiplier, jm->mimic->offset);
415 RCLCPP_ERROR(LOGGER,
"Joint '%s' cannot mimic joint '%s' because they have different number of DOF",
416 joint_model->getName().c_str(), jm->mimic->joint_name.c_str());
421 RCLCPP_ERROR(LOGGER,
"Joint '%s' cannot mimic unknown joint '%s'", joint_model->getName().c_str(),
422 jm->mimic->joint_name.c_str());
435 if (joint_model->getMimic())
437 if (joint_model->getMimic()->getMimic())
439 joint_model->setMimic(joint_model->getMimic()->getMimic(),
440 joint_model->getMimicFactor() * joint_model->getMimic()->getMimicFactor(),
441 joint_model->getMimicOffset() +
442 joint_model->getMimicFactor() * joint_model->getMimic()->getMimicOffset());
445 if (joint_model == joint_model->getMimic())
447 RCLCPP_ERROR(LOGGER,
"Cycle found in joint that mimic each other. Ignoring all mimic joints.");
449 joint_model_recal->setMimic(
nullptr, 0.0, 0.0);
459 if (joint_model->getMimic())
461 const_cast<JointModel*
>(joint_model->getMimic())->addMimicRequest(joint_model);
480 RCLCPP_ERROR(LOGGER,
"End-effector '%s' not found in model '%s'",
name.c_str(),
model_name_.c_str());
494 RCLCPP_ERROR(LOGGER,
"End-effector '%s' not found in model '%s'",
name.c_str(),
model_name_.c_str());
510 RCLCPP_ERROR(LOGGER,
"Group '%s' not found in model '%s'",
name.c_str(),
model_name_.c_str());
521 RCLCPP_ERROR(LOGGER,
"Group '%s' not found in model '%s'",
name.c_str(),
model_name_.c_str());
527 void RobotModel::buildGroups(
const srdf::Model& srdf_model)
529 const std::vector<srdf::Model::Group>& group_configs = srdf_model.getGroups();
532 std::vector<bool> processed(group_configs.size(),
false);
540 for (std::size_t i = 0; i < group_configs.size(); ++i)
545 bool all_subgroups_added =
true;
546 for (
const std::string& subgroup : group_configs[i].subgroups_)
550 all_subgroups_added =
false;
554 if (all_subgroups_added)
558 if (!addJointModelGroup(group_configs[i]))
560 RCLCPP_WARN(LOGGER,
"Failed to add group '%s'", group_configs[i].name_.c_str());
567 for (std::size_t i = 0; i < processed.size(); ++i)
571 RCLCPP_WARN(LOGGER,
"Could not process group '%s' due to unmet subgroup dependencies",
572 group_configs[i].name_.c_str());
585 buildGroupsInfoSubgroups();
586 buildGroupsInfoEndEffectors(srdf_model);
589 void RobotModel::buildGroupsInfoSubgroups()
594 JointModelGroup* jmg = it->second;
595 std::vector<std::string> subgroup_names;
596 std::set<const JointModel*> joints(jmg->getJointModels().begin(), jmg->getJointModels().end());
600 if (jt->first != it->first)
603 JointModelGroup* sub_jmg = jt->second;
604 const std::vector<const JointModel*>& sub_joints = sub_jmg->getJointModels();
605 for (
const JointModel* sub_joint : sub_joints)
607 if (joints.find(sub_joint) == joints.end())
614 subgroup_names.push_back(sub_jmg->getName());
617 if (!subgroup_names.empty())
618 jmg->setSubgroupNames(subgroup_names);
622 void RobotModel::buildGroupsInfoEndEffectors(
const srdf::Model& srdf_model)
625 const std::vector<srdf::Model::EndEffector>& eefs = srdf_model.getEndEffectors();
629 for (
const srdf::Model::EndEffector& eef : eefs)
631 if (eef.component_group_ == it->first)
634 it->second->setEndEffectorName(eef.name_);
640 std::vector<JointModelGroup*> possible_parent_groups;
644 if (jt->first != it->first)
646 if (jt->second->hasLinkModel(eef.parent_link_))
648 jt->second->attachEndEffector(eef.name_);
649 possible_parent_groups.push_back(jt->second);
654 JointModelGroup* eef_parent_group =
nullptr;
656 if (!eef.parent_group_.empty())
661 if (jt->second->hasLinkModel(eef.parent_link_))
663 if (jt->second != it->second)
665 eef_parent_group = jt->second;
669 RCLCPP_ERROR(LOGGER,
"Group '%s' for end-effector '%s' cannot be its own parent",
670 eef.parent_group_.c_str(), eef.name_.c_str());
676 "Group '%s' was specified as parent group for end-effector '%s' "
677 "but it does not include the parent link '%s'",
678 eef.parent_group_.c_str(), eef.name_.c_str(), eef.parent_link_.c_str());
683 RCLCPP_ERROR(LOGGER,
"Group name '%s' not found (specified as parent group for end-effector '%s')",
684 eef.parent_group_.c_str(), eef.name_.c_str());
689 if (eef_parent_group ==
nullptr)
691 if (!possible_parent_groups.empty())
695 std::size_t best = 0;
696 for (std::size_t g = 1; g < possible_parent_groups.size(); ++g)
702 eef_parent_group = possible_parent_groups[best];
706 if (eef_parent_group)
708 it->second->setEndEffectorParent(eef_parent_group->getName(), eef.parent_link_);
712 RCLCPP_WARN(LOGGER,
"Could not identify parent group for end-effector '%s'", eef.name_.c_str());
713 it->second->setEndEffectorParent(
"", eef.parent_link_);
721 bool RobotModel::addJointModelGroup(
const srdf::Model::Group& gc)
725 RCLCPP_WARN(LOGGER,
"A group named '%s' already exists. Not adding.", gc.name_.c_str());
729 std::set<const JointModel*> jset;
732 for (
const std::pair<std::string, std::string>&
chain : gc.chains_)
736 if (base_link && tip_link)
739 const LinkModel* lm = tip_link;
740 std::vector<const JointModel*> cj;
745 cj.push_back(lm->getParentJointModel());
746 lm = lm->getParentJointModel()->getParentLinkModel();
754 std::size_t index = 0;
755 std::vector<const JointModel*> cj2;
758 for (std::size_t j = 0; j < cj.size(); ++j)
760 if (cj[j] == lm->getParentJointModel())
768 cj2.push_back(lm->getParentJointModel());
769 lm = lm->getParentJointModel()->getParentLinkModel();
773 jset.insert(cj.begin(), cj.begin() + index);
774 jset.insert(cj2.begin(), cj2.end());
780 jset.insert(cj.begin(), cj.end());
786 for (
const std::string& joint : gc.joints_)
794 for (
const std::string& link : gc.links_)
798 jset.insert(l->getParentJointModel());
802 for (
const std::string& subgroup : gc.subgroups_)
808 const std::vector<const JointModel*>& js = sg->getJointModels();
809 for (
const JointModel* j : js)
813 const std::vector<const JointModel*>& fs = sg->getFixedJointModels();
814 for (
const JointModel*
f : fs)
818 const std::vector<const JointModel*>& ms = sg->getMimicJointModels();
819 for (
const JointModel* m : ms)
826 RCLCPP_WARN(LOGGER,
"Group '%s' must have at least one valid joint", gc.name_.c_str());
830 std::vector<const JointModel*> joints;
831 joints.reserve(jset.size());
832 for (
const JointModel* it : jset)
833 joints.push_back(it);
835 JointModelGroup* jmg =
new JointModelGroup(gc.name_, gc, joints,
this);
841 JointModel* RobotModel::buildRecursive(LinkModel* parent,
const urdf::Link* urdf_link,
const srdf::Model& srdf_model)
844 JointModel* joint = constructJointModel(urdf_link, srdf_model);
846 if (joint ==
nullptr)
854 joint->setParentLinkModel(parent);
857 LinkModel* link = constructLinkModel(urdf_link);
858 joint->setChildLinkModel(link);
859 link->setParentLinkModel(parent);
866 if (!link->getShapes().empty())
873 link->setParentJointModel(joint);
876 for (
const urdf::LinkSharedPtr& child_link : urdf_link->child_links)
878 JointModel* jm = buildRecursive(link, child_link.get(), srdf_model);
880 link->addChildJointModel(jm);
888 static inline VariableBounds jointBoundsFromURDF(
const urdf::Joint* urdf_joint)
891 if (urdf_joint->safety)
893 b.position_bounded_ =
true;
894 b.min_position_ = urdf_joint->safety->soft_lower_limit;
895 b.max_position_ = urdf_joint->safety->soft_upper_limit;
896 if (urdf_joint->limits)
898 if (urdf_joint->limits->lower > b.min_position_)
899 b.min_position_ = urdf_joint->limits->lower;
900 if (urdf_joint->limits->upper < b.max_position_)
901 b.max_position_ = urdf_joint->limits->upper;
906 if (urdf_joint->limits)
908 b.position_bounded_ =
true;
909 b.min_position_ = urdf_joint->limits->lower;
910 b.max_position_ = urdf_joint->limits->upper;
913 if (urdf_joint->limits)
915 b.max_velocity_ = fabs(urdf_joint->limits->velocity);
916 b.min_velocity_ = -b.max_velocity_;
917 b.velocity_bounded_ = b.max_velocity_ > std::numeric_limits<double>::epsilon();
923 JointModel* RobotModel::constructJointModel(
const urdf::Link* child_link,
const srdf::Model& srdf_model)
925 JointModel* new_joint_model =
nullptr;
926 auto parent_joint = child_link->parent_joint ? child_link->parent_joint.get() :
nullptr;
935 switch (parent_joint->type)
937 case urdf::Joint::REVOLUTE:
939 RevoluteJointModel* j =
new RevoluteJointModel(parent_joint->name, joint_index, first_variable_index);
940 j->setVariableBounds(j->getName(), jointBoundsFromURDF(parent_joint));
941 j->setContinuous(
false);
942 j->setAxis(
Eigen::Vector3d(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z));
946 case urdf::Joint::CONTINUOUS:
948 RevoluteJointModel* j =
new RevoluteJointModel(parent_joint->name, joint_index, first_variable_index);
949 j->setVariableBounds(j->getName(), jointBoundsFromURDF(parent_joint));
950 j->setContinuous(
true);
951 j->setAxis(
Eigen::Vector3d(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z));
955 case urdf::Joint::PRISMATIC:
957 PrismaticJointModel* j =
new PrismaticJointModel(parent_joint->name, joint_index, first_variable_index);
958 j->setVariableBounds(j->getName(), jointBoundsFromURDF(parent_joint));
959 j->setAxis(
Eigen::Vector3d(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z));
963 case urdf::Joint::FLOATING:
964 new_joint_model =
new FloatingJointModel(parent_joint->name, joint_index, first_variable_index);
966 case urdf::Joint::PLANAR:
967 new_joint_model =
new PlanarJointModel(parent_joint->name, joint_index, first_variable_index);
970 new_joint_model =
new FixedJointModel(parent_joint->name, joint_index, first_variable_index);
973 RCLCPP_ERROR(LOGGER,
"Unknown joint type: %d",
static_cast<int>(parent_joint->type));
979 const std::vector<srdf::Model::VirtualJoint>& virtual_joints = srdf_model.getVirtualJoints();
980 for (
const srdf::Model::VirtualJoint& virtual_joint : virtual_joints)
982 if (virtual_joint.child_link_ != child_link->name)
984 if (child_link->name ==
"world" && virtual_joint.type_ ==
"fixed" && child_link->collision_array.empty() &&
985 !child_link->collision && child_link->visual_array.empty() && !child_link->visual)
989 new_joint_model =
new FixedJointModel(virtual_joint.name_, joint_index, first_variable_index);
994 "Skipping virtual joint '%s' because its child frame '%s' "
995 "does not match the URDF frame '%s'",
996 virtual_joint.name_.c_str(), virtual_joint.child_link_.c_str(), child_link->name.c_str());
999 else if (virtual_joint.parent_frame_.empty())
1001 RCLCPP_WARN(LOGGER,
"Skipping virtual joint '%s' because its parent frame is empty",
1002 virtual_joint.name_.c_str());
1006 if (virtual_joint.type_ ==
"fixed")
1008 new_joint_model =
new FixedJointModel(virtual_joint.name_, joint_index, first_variable_index);
1010 else if (virtual_joint.type_ ==
"planar")
1012 new_joint_model =
new PlanarJointModel(virtual_joint.name_, joint_index, first_variable_index);
1014 else if (virtual_joint.type_ ==
"floating")
1016 new_joint_model =
new FloatingJointModel(virtual_joint.name_, joint_index, first_variable_index);
1018 if (new_joint_model)
1021 if (virtual_joint.type_ !=
"fixed")
1029 if (!new_joint_model)
1031 RCLCPP_INFO(LOGGER,
"No root/virtual joint specified in SRDF. Assuming fixed joint");
1032 new_joint_model =
new FixedJointModel(
"ASSUMED_FIXED_ROOT_JOINT", joint_index, first_variable_index);
1036 if (new_joint_model)
1038 new_joint_model->setDistanceFactor(new_joint_model->getStateSpaceDimension());
1039 const std::vector<srdf::Model::PassiveJoint>& pjoints = srdf_model.getPassiveJoints();
1040 for (
const srdf::Model::PassiveJoint& pjoint : pjoints)
1042 if (new_joint_model->getName() == pjoint.name_)
1044 new_joint_model->setPassive(
true);
1049 for (
const srdf::Model::JointProperty& property : srdf_model.getJointProperties(new_joint_model->getName()))
1051 if (property.property_name_ ==
"angular_distance_weight")
1053 double angular_distance_weight;
1056 std::string::size_type sz;
1057 angular_distance_weight = std::stod(property.value_, &sz);
1058 if (sz != property.value_.size())
1060 RCLCPP_WARN_STREAM(LOGGER,
"Extra characters after property " << property.property_name_ <<
" for joint "
1061 << property.joint_name_ <<
" as double: '"
1062 << property.value_.substr(sz) <<
'\'');
1065 catch (
const std::invalid_argument& e)
1067 RCLCPP_ERROR_STREAM(LOGGER,
"Unable to parse property " << property.property_name_ <<
" for joint "
1068 << property.joint_name_ <<
" as double: '"
1069 << property.value_ <<
'\'');
1073 if (new_joint_model->getType() == JointModel::JointType::PLANAR)
1075 static_cast<PlanarJointModel*
>(new_joint_model)->setAngularDistanceWeight(angular_distance_weight);
1077 else if (new_joint_model->getType() == JointModel::JointType::FLOATING)
1079 static_cast<FloatingJointModel*
>(new_joint_model)->setAngularDistanceWeight(angular_distance_weight);
1083 RCLCPP_ERROR_STREAM(LOGGER,
"Cannot apply property " << property.property_name_
1084 <<
" to joint type: " << new_joint_model->getTypeName());
1087 else if (property.property_name_ ==
"motion_model")
1089 if (new_joint_model->getType() != JointModel::JointType::PLANAR)
1091 RCLCPP_ERROR(LOGGER,
"Cannot apply property %s to joint type: %s", property.property_name_.c_str(),
1092 new_joint_model->getTypeName().c_str());
1097 if (property.value_ ==
"holonomic")
1099 motion_model = PlanarJointModel::MotionModel::HOLONOMIC;
1101 else if (property.value_ ==
"diff_drive")
1103 motion_model = PlanarJointModel::MotionModel::DIFF_DRIVE;
1107 RCLCPP_ERROR_STREAM(LOGGER,
"Unknown value for property " << property.property_name_ <<
" ("
1108 << property.joint_name_ <<
"): '" << property.value_
1110 RCLCPP_ERROR(LOGGER,
"Valid values are 'holonomic' and 'diff_drive'");
1114 static_cast<PlanarJointModel*
>(new_joint_model)->setMotionModel(motion_model);
1116 else if (property.property_name_ ==
"min_translational_distance")
1118 if (new_joint_model->getType() != JointModel::JointType::PLANAR)
1120 RCLCPP_ERROR(LOGGER,
"Cannot apply property %s to joint type: %s", property.property_name_.c_str(),
1121 new_joint_model->getTypeName().c_str());
1124 double min_translational_distance;
1127 std::string::size_type sz;
1128 min_translational_distance = std::stod(property.value_, &sz);
1129 if (sz != property.value_.size())
1131 RCLCPP_WARN_STREAM(LOGGER,
"Extra characters after property " << property.property_name_ <<
" for joint "
1132 << property.joint_name_ <<
" as double: '"
1133 << property.value_.substr(sz) <<
'\'');
1136 catch (
const std::invalid_argument& e)
1138 RCLCPP_ERROR_STREAM(LOGGER,
"Unable to parse property " << property.property_name_ <<
" for joint "
1139 << property.joint_name_ <<
" as double: '"
1140 << property.value_ <<
'\'');
1144 static_cast<PlanarJointModel*
>(new_joint_model)->setMinTranslationalDistance(min_translational_distance);
1148 RCLCPP_ERROR(LOGGER,
"Unknown joint property: %s", property.property_name_.c_str());
1153 return new_joint_model;
1158 static inline Eigen::Isometry3d urdfPose2Isometry3d(
const urdf::Pose& pose)
1160 Eigen::Quaterniond q(pose.rotation.w, pose.rotation.x, pose.rotation.y, pose.rotation.z);
1161 Eigen::Isometry3d af(Eigen::Translation3d(pose.position.x, pose.position.y, pose.position.z) * q);
1166 LinkModel* RobotModel::constructLinkModel(
const urdf::Link* urdf_link)
1169 LinkModel* new_link_model =
new LinkModel(urdf_link->name, link_index);
1171 const std::vector<urdf::CollisionSharedPtr>& col_array =
1172 urdf_link->collision_array.empty() ? std::vector<urdf::CollisionSharedPtr>(1, urdf_link->collision) :
1173 urdf_link->collision_array;
1175 std::vector<shapes::ShapeConstPtr>
shapes;
1176 EigenSTL::vector_Isometry3d poses;
1178 for (
const urdf::CollisionSharedPtr& col : col_array)
1180 if (col && col->geometry)
1182 shapes::ShapeConstPtr s = constructShape(col->geometry.get());
1186 poses.push_back(urdfPose2Isometry3d(col->origin));
1192 bool warn_about_missing_collision =
false;
1195 const auto& vis_array = urdf_link->visual_array.empty() ? std::vector<urdf::VisualSharedPtr>{ urdf_link->visual } :
1196 urdf_link->visual_array;
1197 for (
const urdf::VisualSharedPtr& vis : vis_array)
1199 if (vis && vis->geometry)
1200 warn_about_missing_collision =
true;
1203 if (warn_about_missing_collision)
1205 RCLCPP_WARN_STREAM(LOGGER,
1206 "Link " << urdf_link->name
1207 <<
" has visual geometry but no collision geometry. "
1208 "Collision geometry will be left empty. "
1209 "Fix your URDF file by explicitly specifying collision geometry.");
1212 new_link_model->setGeometry(
shapes, poses);
1215 if (urdf_link->visual && urdf_link->visual->geometry)
1217 if (urdf_link->visual->geometry->type == urdf::Geometry::MESH)
1219 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(urdf_link->visual->geometry.get());
1220 if (!mesh->filename.empty())
1222 new_link_model->setVisualMesh(mesh->filename, urdfPose2Isometry3d(urdf_link->visual->origin),
1227 else if (urdf_link->collision && urdf_link->collision->geometry)
1229 if (urdf_link->collision->geometry->type == urdf::Geometry::MESH)
1231 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(urdf_link->collision->geometry.get());
1232 if (!mesh->filename.empty())
1234 new_link_model->setVisualMesh(mesh->filename, urdfPose2Isometry3d(urdf_link->collision->origin),
1240 if (urdf_link->parent_joint)
1242 new_link_model->setJointOriginTransform(
1243 urdfPose2Isometry3d(urdf_link->parent_joint->parent_to_joint_origin_transform));
1246 return new_link_model;
1249 shapes::ShapePtr RobotModel::constructShape(
const urdf::Geometry* geom)
1251 shapes::Shape* new_shape =
nullptr;
1254 case urdf::Geometry::SPHERE:
1255 new_shape =
new shapes::Sphere(
static_cast<const urdf::Sphere*
>(geom)->radius);
1257 case urdf::Geometry::BOX:
1259 urdf::Vector3 dim =
static_cast<const urdf::Box*
>(geom)->dim;
1260 new_shape =
new shapes::Box(dim.x, dim.y, dim.z);
1263 case urdf::Geometry::CYLINDER:
1264 new_shape =
new shapes::Cylinder(
static_cast<const urdf::Cylinder*
>(geom)->radius,
1265 static_cast<const urdf::Cylinder*
>(geom)->length);
1267 case urdf::Geometry::MESH:
1269 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(geom);
1270 if (!mesh->filename.empty())
1273 shapes::Mesh* m = shapes::createMeshFromResource(mesh->filename, scale);
1279 RCLCPP_ERROR(LOGGER,
"Unknown geometry type: %d",
static_cast<int>(geom->type));
1283 return shapes::ShapePtr(new_shape);
1301 RCLCPP_ERROR(LOGGER,
"Joint '%s' not found in model '%s'",
name.c_str(),
model_name_.c_str());
1309 RCLCPP_ERROR(LOGGER,
"Joint index '%li' out of bounds of joints in model '%s'", index,
model_name_.c_str());
1321 RCLCPP_ERROR(LOGGER,
"Joint '%s' not found in model '%s'",
name.c_str(),
model_name_.c_str());
1334 RCLCPP_ERROR(LOGGER,
"Link index '%li' out of bounds of links in model '%s'", index,
model_name_.c_str());
1355 RCLCPP_ERROR(LOGGER,
"Link '%s' not found in model '%s'",
name.c_str(),
model_name_.c_str());
1380 int src = mimic_joint->getMimic()->getFirstVariableIndex();
1381 int dest = mimic_joint->getFirstVariableIndex();
1382 values[
dest] = values[src] * mimic_joint->getMimicFactor() + mimic_joint->getMimicOffset();
1394 std::map<std::string, double>& values)
const
1420 std::vector<std::string>& missing_variables)
const
1422 missing_variables.clear();
1423 std::set<std::string> keys(variables.begin(), variables.end());
1426 if (keys.find(variable_name) == keys.end())
1429 missing_variables.push_back(variable_name);
1444 double max_distance = 0.0;
1450 return max_distance;
1454 double margin)
const
1460 *active_joint_bounds[i], margin))
1469 bool change =
false;
1473 *active_joint_bounds[i]))
1495 moveit::core::checkInterpolationParamBounds(LOGGER, t);
1512 std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->getName());
1513 if (jt != allocators.end())
1515 std::pair<SolverAllocatorFn, SolverAllocatorMapFn> solver_allocator_pair;
1516 solver_allocator_pair.first = jt->second;
1517 jmg->setSolverAllocators(solver_allocator_pair);
1525 std::pair<SolverAllocatorFn, SolverAllocatorMapFn> solver_allocator_pair;
1526 std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->getName());
1527 if (jt == allocators.end())
1530 std::set<const JointModel*> joints;
1531 joints.insert(jmg->getJointModels().begin(), jmg->getJointModels().end());
1533 std::vector<const JointModelGroup*> subs;
1536 for (
const std::pair<const std::string, SolverAllocatorFn>& allocator : allocators)
1544 std::set<const JointModel*> sub_joints;
1547 if (std::includes(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end()))
1549 std::set<const JointModel*> joint_model_set;
1550 std::set_difference(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end(),
1551 std::inserter(joint_model_set, joint_model_set.end()));
1557 subs.push_back(sub);
1558 joints.swap(joint_model_set);
1565 std::stringstream ss;
1568 ss << sub->getName() <<
' ';
1569 solver_allocator_pair.second[sub] = allocators.find(sub->getName())->second;
1571 RCLCPP_DEBUG(LOGGER,
"Added sub-group IK allocators for group '%s': [ %s]", jmg->getName().c_str(),
1574 jmg->setSolverAllocators(solver_allocator_pair);
1583 std::ios_base::fmtflags old_flags = out.flags();
1584 out.setf(std::ios::fixed, std::ios::floatfield);
1585 std::streamsize old_prec = out.precision();
1587 out <<
"Joints: \n";
1590 out <<
" '" << joint_model->getName() <<
"' (" << joint_model->getTypeName() <<
")\n";
1591 out <<
" * Joint Index: " << joint_model->getJointIndex() <<
'\n';
1592 const std::vector<std::string>& vn = joint_model->getVariableNames();
1593 out <<
" * " << vn.size() << (vn.size() > 1 ?
" variables:" : (vn.empty() ?
" variables" :
" variable:\n"));
1594 int idx = joint_model->getFirstVariableIndex();
1595 for (
const std::string& it : vn)
1597 out <<
" * '" << it <<
"', index " << idx++ <<
" in full state";
1598 if (joint_model->getMimic())
1599 out <<
", mimic '" << joint_model->getMimic()->getName() <<
'\'';
1600 if (joint_model->isPassive())
1603 out <<
" " << joint_model->getVariableBounds(it) <<
'\n';
1607 out.precision(old_prec);
1608 out.flags(old_flags);
1612 out <<
" '" << link_model->getName() <<
"' with " << link_model->getShapes().size() <<
" geoms\n";
1613 if (link_model->parentJointIsFixed())
1616 <<
"parent joint is fixed" <<
'\n';
1618 if (link_model->jointOriginTransformIsIdentity())
1621 <<
"joint origin transform is identity\n";
1625 out <<
"Available groups: \n";
1627 joint_model_group->printGroupInfo(out);
This may be thrown if unrecoverable errors occur.
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
JointType getType() const
Get the type of joint.
A link from the robot. Contains the constant transform applied to the link and its geometry.
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
const Eigen::Isometry3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link's origin....
const LinkModel * getParentLinkModel() const
Get the link model whose child this link is (through some joint). There may not always be a parent li...
const std::vector< const JointModel * > & getChildJointModels() const
A link may have 0 or more child joints. From those joints there will certainly be other descendant li...
MotionModel
different types of planar joints we support
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
std::size_t link_geometry_count_
Total number of geometric shapes in this model.
std::size_t getVariableCount() const
Get the number of variables that describe this model.
std::string model_frame_
The reference (base) frame for this model. The frame is either extracted from the SRDF as a virtual j...
std::vector< const JointModel * > single_dof_joints_
std::vector< const JointModel * > joint_model_vector_const_
The vector of joints in the model, in the order they appear in the state vector.
std::vector< std::string > link_model_names_with_collision_geometry_vector_
The vector of link names that corresponds to link_models_with_collision_geometry_vector_.
std::vector< std::string > joint_model_group_names_
A vector of all group names, in alphabetical order.
std::vector< const LinkModel * > link_models_with_collision_geometry_vector_
Only links that have collision geometry specified.
void updateMimicJoints(double *values) const
Update the variable values for the state of a group with respect to the mimic joints.
bool hasJointModelGroup(const std::string &group) const
Check if the JointModelGroup group exists.
srdf::ModelConstSharedPtr srdf_
void computeFixedTransforms(const LinkModel *link, const Eigen::Isometry3d &transform, LinkTransformMap &associated_transforms)
Get the transforms between link and all its rigidly attached descendants.
const std::vector< const JointModel * > & getJointModels() const
Get the array of joints, in the order they appear in the robot state.
std::vector< const LinkModel * > link_model_vector_const_
The vector of links that are updated when computeTransforms() is called, in the order they are update...
std::vector< std::string > link_model_names_vector_
The vector of link names that corresponds to link_model_vector_.
std::vector< int > common_joint_roots_
For every two joints, the index of the common root for the joints is stored.
std::vector< JointModelGroup * > joint_model_groups_
The array of joint model groups, in alphabetical order.
bool hasEndEffector(const std::string &eef) const
Check if an end effector exists.
void interpolate(const double *from, const double *to, double t, double *state) const
std::vector< JointModel * > joint_model_vector_
The vector of joints in the model, in the order they appear in the state vector.
std::vector< const JointModel * > mimic_joints_
The set of mimic joints this model contains.
const LinkModel * getRootLink() const
Get the physical root link of the robot.
const JointModel * getRootJoint() const
Get the root joint. There will be one root joint unless the model is empty. This is either extracted ...
bool hasJointModel(const std::string &name) const
Check if a joint exists. Return true if it does.
size_t getVariableIndex(const std::string &variable) const
Get the index of a variable in the robot state.
~RobotModel()
Destructor. Clear all memory.
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute the random values for a RobotState.
JointBoundsVector active_joint_models_bounds_
The bounds for all the active joint models.
std::vector< const JointModel * > active_joint_model_vector_const_
The vector of joints in the model, in the order they appear in the state vector.
std::vector< const JointModel * > joints_of_variable_
The joints that correspond to each variable index.
LinkModelMap link_model_map_
A map from link names to their instances.
void getVariableDefaultPositions(double *values) const
Compute the default values for a RobotState.
std::vector< std::string > active_joint_model_names_vector_
The vector of joint names that corresponds to active_joint_model_vector_.
std::vector< std::string > variable_names_
The names of the DOF that make up this state (this is just a sequence of joint variable names; not ne...
std::vector< int > active_joint_model_start_index_
urdf::ModelInterfaceSharedPtr urdf_
std::vector< const JointModelGroup * > joint_model_groups_const_
The array of joint model groups, in alphabetical order.
std::vector< LinkModel * > link_model_vector_
The vector of links that are updated when computeTransforms() is called, in the order they are update...
VariableIndexMap joint_variables_index_map_
The state includes all the joint variables that make up the joints the state consists of....
const JointModelGroup * getEndEffector(const std::string &name) const
Get the joint group that corresponds to a given end-effector name.
JointModelGroupMap joint_model_group_map_
A map from group names to joint groups.
std::vector< const JointModelGroup * > end_effectors_
The array of end-effectors, in alphabetical order.
void getMissingVariableNames(const std::vector< std::string > &variables, std::vector< std::string > &missing_variables) const
RobotModel(const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model)
Construct a kinematic model from a parsed description and a list of planning groups.
std::vector< const JointModel * > multi_dof_joints_
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
std::vector< const JointModel * > continuous_joint_model_vector_
The set of continuous joints this model contains.
JointModelGroupMap end_effectors_map_
The known end effectors.
static const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const LinkModel *link)
Get the latest link upwards the kinematic tree, which is only connected via fixed joints.
void printModelInfo(std::ostream &out) const
Print information about the constructed model.
std::vector< std::string > joint_model_names_vector_
The vector of joint names that corresponds to joint_model_vector_.
double distance(const double *state1, const double *state2) const
Return the sum of joint distances between two states. An L1 norm. Only considers active joints.
const JointModel * getJointOfVariable(int variable_index) const
bool hasLinkModel(const std::string &name) const
Check if a link exists. Return true if it does.
JointModelMap joint_model_map_
A map from joint names to their instances.
std::size_t variable_count_
Get the number of variables necessary to describe this model.
double getMaximumExtent() const
std::string model_name_
The name of the robot.
const LinkModel * root_link_
The first physical link for the robot.
const LinkModel * getLinkModel(const std::string &link, bool *has_link=nullptr) const
Get a link by its name. Output error and return nullptr when the link is missing.
bool satisfiesPositionBounds(const double *state, double margin=0.0) const
std::vector< JointModel * > active_joint_model_vector_
The vector of joints in the model, in the order they appear in the state vector.
void setKinematicsAllocators(const std::map< std::string, SolverAllocatorFn > &allocators)
A map of known kinematics solvers (associated to their group name)
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Output error and return nullptr when the joint is missing.
const JointModel * root_joint_
The root joint.
const std::string & getName() const
Get the model name.
bool enforcePositionBounds(double *state) const
Vec3fX< details::Vec3Data< double > > Vector3d
std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
std::vector< const JointModel::Bounds * > JointBoundsVector
Main namespace for MoveIt.
FilterFn chain(const std::vector< FilterFn > &filter_functions)