39#include <geometric_shapes/shape_operations.h>
40#include <rclcpp/logger.hpp>
66 buildModel(*urdf_model, *srdf_model);
89void RobotModel::buildModel(
const urdf::ModelInterface& urdf_model,
const srdf::Model& srdf_model)
96 RCLCPP_INFO(getLogger(),
"Loading robot model '%s'...",
model_name_.c_str());
98 if (urdf_model.getRoot())
100 const urdf::Link* root_link_ptr = urdf_model.getRoot().get();
103 RCLCPP_DEBUG(getLogger(),
"... building kinematic chain");
104 root_joint_ = buildRecursive(
nullptr, root_link_ptr, srdf_model);
107 RCLCPP_DEBUG(getLogger(),
"... building mimic joints");
108 buildMimic(urdf_model);
110 RCLCPP_DEBUG(getLogger(),
"... computing joint indexing");
115 RCLCPP_WARN(getLogger(),
"No geometry is associated to any robot links");
120 RCLCPP_DEBUG(getLogger(),
"... constructing joint groups");
121 buildGroups(srdf_model);
123 RCLCPP_DEBUG(getLogger(),
"... constructing joint group states");
124 buildGroupStates(srdf_model);
131 RCLCPP_WARN(getLogger(),
"No root link found");
137typedef std::map<const JointModel*, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
138 std::set<const JointModel*, OrderJointsByIndex>>>
141void computeDescendantsHelper(
const JointModel* joint, std::vector<const JointModel*>& parents,
142 std::set<const JointModel*>& seen, DescMap& descendants)
146 if (seen.find(joint) != seen.end())
150 for (
const JointModel* parent : parents)
151 descendants[parent].second.insert(joint);
153 const LinkModel* lm = joint->getChildLinkModel();
157 for (
const JointModel* parent : parents)
158 descendants[parent].first.insert(lm);
159 descendants[joint].first.insert(lm);
161 parents.push_back(joint);
162 const std::vector<const JointModel*>& ch = lm->getChildJointModels();
163 for (
const JointModel* child_joint_model : ch)
164 computeDescendantsHelper(child_joint_model, parents, seen, descendants);
165 const std::vector<const JointModel*>& mim = joint->getMimicRequests();
166 for (
const JointModel* mimic_joint_model : mim)
167 computeDescendantsHelper(mimic_joint_model, parents, seen, descendants);
171void computeCommonRootsHelper(
const JointModel* joint, std::vector<int>& common_roots,
int size)
175 const LinkModel* lm = joint->getChildLinkModel();
179 const std::vector<const JointModel*>& ch = lm->getChildJointModels();
180 for (std::size_t i = 0; i < ch.size(); ++i)
182 const std::vector<const JointModel*>& a = ch[i]->getDescendantJointModels();
183 for (std::size_t j = i + 1; j < ch.size(); ++j)
185 const std::vector<const JointModel*>& b = ch[j]->getDescendantJointModels();
186 for (
const JointModel* m : b)
188 common_roots[ch[i]->getJointIndex() * size + m->getJointIndex()] =
189 common_roots[ch[i]->getJointIndex() + m->getJointIndex() * size] = joint->getJointIndex();
191 for (
const JointModel* k : a)
193 common_roots[k->getJointIndex() * size + ch[j]->getJointIndex()] =
194 common_roots[k->getJointIndex() + ch[j]->getJointIndex() * size] = joint->getJointIndex();
195 for (
const JointModel* m : b)
197 common_roots[k->getJointIndex() * size + m->getJointIndex()] =
198 common_roots[k->getJointIndex() + m->getJointIndex() * size] = joint->getJointIndex();
202 computeCommonRootsHelper(ch[i], common_roots, size);
207void RobotModel::computeCommonRoots()
229 const std::vector<const JointModel*>& d = joint_model->getDescendantJointModels();
230 for (
const JointModel* descendant_joint_model : d)
233 joint_model->getJointIndex()] =
240void RobotModel::computeDescendants()
243 std::vector<const JointModel*> parents;
244 std::set<const JointModel*> seen;
247 computeDescendantsHelper(
root_joint_, parents, seen, descendants);
248 for (std::pair<
const JointModel*
const, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
249 std::set<const JointModel*, OrderJointsByIndex>>>& descendant :
252 JointModel* jm =
const_cast<JointModel*
>(descendant.first);
253 for (
const JointModel* jt : descendant.second.second)
254 jm->addDescendantJointModel(jt);
255 for (
const LinkModel* jt : descendant.second.first)
256 jm->addDescendantLinkModel(jt);
260void RobotModel::buildJointInfo()
270 const std::vector<std::string>& name_order = joint->getVariableNames();
273 if (!name_order.empty())
275 for (std::size_t j = 0; j < name_order.size(); ++j)
281 if (joint->getMimic() ==
nullptr)
290 if (joint->getType() ==
JointModel::REVOLUTE &&
static_cast<const RevoluteJointModel*
>(joint)->isContinuous())
296 std::size_t vc = joint->getVariableCount();
312 if (link_considered[link->getLinkIndex()])
317 for (
auto& tf_base : associated_transforms)
319 link_considered[tf_base.first->getLinkIndex()] =
true;
320 for (
auto& tf_target : associated_transforms)
322 if (&tf_base != &tf_target)
324 const_cast<LinkModel*
>(tf_base.first)
325 ->addAssociatedFixedTransform(tf_target.first, tf_base.second.inverse() * tf_target.second);
331 computeDescendants();
332 computeCommonRoots();
335void RobotModel::buildGroupStates(
const srdf::Model& srdf_model)
338 const std::vector<srdf::Model::GroupState>& ds = srdf_model.getGroupStates();
339 for (
const srdf::Model::GroupState& group_state : ds)
344 std::vector<const JointModel*> remaining_joints = jmg->getActiveJointModels();
345 std::map<std::string, double> state;
346 for (std::map<std::string, std::vector<double>>::const_iterator jt = group_state.joint_values_.begin();
347 jt != group_state.joint_values_.end(); ++jt)
349 if (jmg->hasJointModel(jt->first))
351 const JointModel* jm = jmg->getJointModel(jt->first);
352 const std::vector<std::string>& vn = jm->getVariableNames();
354 auto it_found = std::find(remaining_joints.begin(), remaining_joints.end(), jm);
355 if (it_found != remaining_joints.end())
356 remaining_joints.erase(it_found);
357 if (vn.size() == jt->second.size())
359 for (std::size_t j = 0; j < vn.size(); ++j)
360 state[vn[j]] = jt->second[j];
365 "The model for joint '%s' requires %d variable values, "
366 "but only %d variable values were supplied in default state '%s' for group '%s'",
367 jt->first.c_str(),
static_cast<int>(vn.size()),
static_cast<int>(jt->second.size()),
368 group_state.name_.c_str(), jmg->getName().c_str());
374 "Group state '%s' specifies value for joint '%s', "
375 "but that joint is not part of group '%s'",
376 group_state.name_.c_str(), jt->first.c_str(), jmg->getName().c_str());
379 if (!remaining_joints.empty())
381 std::stringstream missing;
382 missing << (*remaining_joints.begin())->
getName();
383 for (
auto j = ++remaining_joints.begin(); j != remaining_joints.end(); ++j)
385 missing <<
", " << (*j)->getName();
387 RCLCPP_WARN_STREAM(
getLogger(),
"Group state '" << group_state.name_
388 <<
"' doesn't specify all group joints in group '"
389 << group_state.group_ <<
"'. " << missing.str() <<
' '
390 << (remaining_joints.size() > 1 ?
"are" :
"is") <<
" missing.");
393 jmg->addDefaultState(group_state.name_, state);
397 RCLCPP_ERROR(
getLogger(),
"Group state '%s' specified for group '%s', but that group does not exist",
398 group_state.name_.c_str(), group_state.group_.c_str());
403void RobotModel::buildMimic(
const urdf::ModelInterface& urdf_model)
408 const urdf::Joint* jm = urdf_model.getJoint(joint_model->getName()).get();
413 JointModelMap::const_iterator jit =
joint_model_map_.find(jm->mimic->joint_name);
416 if (joint_model->getVariableCount() == jit->second->getVariableCount())
418 joint_model->setMimic(jit->second, jm->mimic->multiplier, jm->mimic->offset);
422 RCLCPP_ERROR(
getLogger(),
"Joint '%s' cannot mimic joint '%s' because they have different number of DOF",
423 joint_model->getName().c_str(), jm->mimic->joint_name.c_str());
428 RCLCPP_ERROR(
getLogger(),
"Joint '%s' cannot mimic unknown joint '%s'", joint_model->getName().c_str(),
429 jm->mimic->joint_name.c_str());
442 if (joint_model->getMimic())
444 if (joint_model->getMimic()->getMimic())
446 joint_model->setMimic(joint_model->getMimic()->getMimic(),
447 joint_model->getMimicFactor() * joint_model->getMimic()->getMimicFactor(),
448 joint_model->getMimicOffset() +
449 joint_model->getMimicFactor() * joint_model->getMimic()->getMimicOffset());
452 if (joint_model == joint_model->getMimic())
454 RCLCPP_ERROR(
getLogger(),
"Cycle found in joint that mimic each other. Ignoring all mimic joints.");
456 joint_model_recal->setMimic(nullptr, 0.0, 0.0);
466 if (joint_model->getMimic())
468 const_cast<JointModel*
>(joint_model->getMimic())->addMimicRequest(joint_model);
487 RCLCPP_ERROR(getLogger(),
"End-effector '%s' not found in model '%s'", name.c_str(),
model_name_.c_str());
501 RCLCPP_ERROR(getLogger(),
"End-effector '%s' not found in model '%s'", name.c_str(),
model_name_.c_str());
517 RCLCPP_ERROR(getLogger(),
"Group '%s' not found in model '%s'", name.c_str(),
model_name_.c_str());
528 RCLCPP_ERROR(getLogger(),
"Group '%s' not found in model '%s'", name.c_str(),
model_name_.c_str());
534void RobotModel::buildGroups(
const srdf::Model& srdf_model)
536 const std::vector<srdf::Model::Group>& group_configs = srdf_model.getGroups();
539 std::vector<bool> processed(group_configs.size(),
false);
547 for (std::size_t i = 0; i < group_configs.size(); ++i)
552 bool all_subgroups_added =
true;
553 for (
const std::string& subgroup : group_configs[i].subgroups_)
557 all_subgroups_added =
false;
561 if (all_subgroups_added)
565 if (!addJointModelGroup(group_configs[i]))
567 RCLCPP_WARN(getLogger(),
"Failed to add group '%s'", group_configs[i].name_.c_str());
574 for (std::size_t i = 0; i < processed.size(); ++i)
578 RCLCPP_WARN(
getLogger(),
"Could not process group '%s' due to unmet subgroup dependencies",
579 group_configs[i].name_.c_str());
592 buildGroupsInfoSubgroups();
593 buildGroupsInfoEndEffectors(srdf_model);
596void RobotModel::buildGroupsInfoSubgroups()
601 JointModelGroup* jmg = it->second;
602 std::vector<std::string> subgroup_names;
603 std::set<const JointModel*> joints(jmg->getJointModels().begin(), jmg->getJointModels().end());
607 if (jt->first != it->first)
610 JointModelGroup* sub_jmg = jt->second;
611 const std::vector<const JointModel*>& sub_joints = sub_jmg->getJointModels();
612 for (
const JointModel* sub_joint : sub_joints)
614 if (joints.find(sub_joint) == joints.end())
621 subgroup_names.push_back(sub_jmg->getName());
624 if (!subgroup_names.empty())
625 jmg->setSubgroupNames(subgroup_names);
629void RobotModel::buildGroupsInfoEndEffectors(
const srdf::Model& srdf_model)
632 const std::vector<srdf::Model::EndEffector>& eefs = srdf_model.getEndEffectors();
636 for (
const srdf::Model::EndEffector& eef : eefs)
638 if (eef.component_group_ == it->first)
641 it->second->setEndEffectorName(eef.name_);
647 std::vector<JointModelGroup*> possible_parent_groups;
651 if (jt->first != it->first)
653 if (jt->second->hasLinkModel(eef.parent_link_))
655 jt->second->attachEndEffector(eef.name_);
656 possible_parent_groups.push_back(jt->second);
661 JointModelGroup* eef_parent_group =
nullptr;
663 if (!eef.parent_group_.empty())
668 if (jt->second->hasLinkModel(eef.parent_link_))
670 if (jt->second != it->second)
672 eef_parent_group = jt->second;
676 RCLCPP_ERROR(
getLogger(),
"Group '%s' for end-effector '%s' cannot be its own parent",
677 eef.parent_group_.c_str(), eef.name_.c_str());
683 "Group '%s' was specified as parent group for end-effector '%s' "
684 "but it does not include the parent link '%s'",
685 eef.parent_group_.c_str(), eef.name_.c_str(), eef.parent_link_.c_str());
690 RCLCPP_ERROR(
getLogger(),
"Group name '%s' not found (specified as parent group for end-effector '%s')",
691 eef.parent_group_.c_str(), eef.name_.c_str());
696 if (eef_parent_group ==
nullptr)
698 if (!possible_parent_groups.empty())
702 std::size_t best = 0;
703 for (std::size_t g = 1; g < possible_parent_groups.size(); ++g)
709 eef_parent_group = possible_parent_groups[best];
713 if (eef_parent_group)
715 it->second->setEndEffectorParent(eef_parent_group->getName(), eef.parent_link_);
719 RCLCPP_WARN(
getLogger(),
"Could not identify parent group for end-effector '%s'", eef.name_.c_str());
720 it->second->setEndEffectorParent(
"", eef.parent_link_);
728bool RobotModel::addJointModelGroup(
const srdf::Model::Group& gc)
732 RCLCPP_WARN(
getLogger(),
"A group named '%s' already exists. Not adding.", gc.name_.c_str());
736 std::set<const JointModel*> jset;
739 for (
const std::pair<std::string, std::string>& chain : gc.chains_)
743 if (base_link && tip_link)
746 const LinkModel* lm = tip_link;
747 std::vector<const JointModel*> cj;
752 cj.push_back(lm->getParentJointModel());
753 lm = lm->getParentJointModel()->getParentLinkModel();
761 std::size_t index = 0;
762 std::vector<const JointModel*> cj2;
765 for (std::size_t j = 0; j < cj.size(); ++j)
767 if (cj[j] == lm->getParentJointModel())
775 cj2.push_back(lm->getParentJointModel());
776 lm = lm->getParentJointModel()->getParentLinkModel();
780 jset.insert(cj.begin(), cj.begin() + index);
781 jset.insert(cj2.begin(), cj2.end());
787 jset.insert(cj.begin(), cj.end());
793 for (
const std::string& joint : gc.joints_)
801 for (
const std::string& link : gc.links_)
805 jset.insert(l->getParentJointModel());
809 for (
const std::string& subgroup : gc.subgroups_)
815 const std::vector<const JointModel*>& js = sg->getJointModels();
816 for (
const JointModel* j : js)
820 const std::vector<const JointModel*>& fs = sg->getFixedJointModels();
821 for (
const JointModel* f : fs)
825 const std::vector<const JointModel*>& ms = sg->getMimicJointModels();
826 for (
const JointModel* m : ms)
833 RCLCPP_WARN(
getLogger(),
"Group '%s' must have at least one valid joint", gc.name_.c_str());
837 std::vector<const JointModel*> joints;
838 joints.reserve(jset.size());
839 for (
const JointModel* it : jset)
840 joints.push_back(it);
842 JointModelGroup* jmg =
new JointModelGroup(gc.name_, gc, joints,
this);
848JointModel* RobotModel::buildRecursive(LinkModel* parent,
const urdf::Link* urdf_link,
const srdf::Model& srdf_model)
851 JointModel* joint = constructJointModel(urdf_link, srdf_model);
853 if (joint ==
nullptr)
861 joint->setParentLinkModel(parent);
864 LinkModel* link = constructLinkModel(urdf_link);
865 joint->setChildLinkModel(link);
866 link->setParentLinkModel(parent);
873 if (!link->getShapes().empty())
880 link->setParentJointModel(joint);
883 for (
const urdf::LinkSharedPtr& child_link : urdf_link->child_links)
885 JointModel* jm = buildRecursive(link, child_link.get(), srdf_model);
887 link->addChildJointModel(jm);
895inline VariableBounds jointBoundsFromURDF(
const urdf::Joint* urdf_joint)
898 if (urdf_joint->safety)
900 b.position_bounded_ =
true;
901 b.min_position_ = urdf_joint->safety->soft_lower_limit;
902 b.max_position_ = urdf_joint->safety->soft_upper_limit;
903 if (urdf_joint->limits)
905 if (urdf_joint->limits->lower > b.min_position_)
906 b.min_position_ = urdf_joint->limits->lower;
907 if (urdf_joint->limits->upper < b.max_position_)
908 b.max_position_ = urdf_joint->limits->upper;
913 if (urdf_joint->limits)
915 b.position_bounded_ =
true;
916 b.min_position_ = urdf_joint->limits->lower;
917 b.max_position_ = urdf_joint->limits->upper;
920 if (urdf_joint->limits)
922 b.max_velocity_ = fabs(urdf_joint->limits->velocity);
923 b.min_velocity_ = -b.max_velocity_;
924 b.velocity_bounded_ = b.max_velocity_ > std::numeric_limits<double>::epsilon();
930JointModel* RobotModel::constructJointModel(
const urdf::Link* child_link,
const srdf::Model& srdf_model)
932 JointModel* new_joint_model =
nullptr;
933 auto parent_joint = child_link->parent_joint ? child_link->parent_joint.get() :
nullptr;
942 switch (parent_joint->type)
944 case urdf::Joint::REVOLUTE:
946 RevoluteJointModel* j =
new RevoluteJointModel(parent_joint->name, joint_index, first_variable_index);
947 j->setVariableBounds(j->getName(), jointBoundsFromURDF(parent_joint));
948 j->setContinuous(
false);
949 j->setAxis(Eigen::Vector3d(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z));
953 case urdf::Joint::CONTINUOUS:
955 RevoluteJointModel* j =
new RevoluteJointModel(parent_joint->name, joint_index, first_variable_index);
956 j->setVariableBounds(j->getName(), jointBoundsFromURDF(parent_joint));
957 j->setContinuous(
true);
958 j->setAxis(Eigen::Vector3d(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z));
962 case urdf::Joint::PRISMATIC:
964 PrismaticJointModel* j =
new PrismaticJointModel(parent_joint->name, joint_index, first_variable_index);
965 j->setVariableBounds(j->getName(), jointBoundsFromURDF(parent_joint));
966 j->setAxis(Eigen::Vector3d(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z));
970 case urdf::Joint::FLOATING:
971 new_joint_model =
new FloatingJointModel(parent_joint->name, joint_index, first_variable_index);
973 case urdf::Joint::PLANAR:
974 new_joint_model =
new PlanarJointModel(parent_joint->name, joint_index, first_variable_index);
976 case urdf::Joint::FIXED:
977 new_joint_model =
new FixedJointModel(parent_joint->name, joint_index, first_variable_index);
980 RCLCPP_ERROR(
getLogger(),
"Unknown joint type: %d",
static_cast<int>(parent_joint->type));
986 const std::vector<srdf::Model::VirtualJoint>& virtual_joints = srdf_model.getVirtualJoints();
987 for (
const srdf::Model::VirtualJoint& virtual_joint : virtual_joints)
989 if (virtual_joint.child_link_ != child_link->name)
991 if (child_link->name ==
"world" && virtual_joint.type_ ==
"fixed" && child_link->collision_array.empty() &&
992 !child_link->collision && child_link->visual_array.empty() && !child_link->visual)
996 new_joint_model =
new FixedJointModel(virtual_joint.name_, joint_index, first_variable_index);
1001 "Skipping virtual joint '%s' because its child frame '%s' "
1002 "does not match the URDF frame '%s'",
1003 virtual_joint.name_.c_str(), virtual_joint.child_link_.c_str(), child_link->name.c_str());
1006 else if (virtual_joint.parent_frame_.empty())
1008 RCLCPP_WARN(
getLogger(),
"Skipping virtual joint '%s' because its parent frame is empty",
1009 virtual_joint.name_.c_str());
1013 if (virtual_joint.type_ ==
"fixed")
1015 new_joint_model =
new FixedJointModel(virtual_joint.name_, joint_index, first_variable_index);
1017 else if (virtual_joint.type_ ==
"planar")
1019 new_joint_model =
new PlanarJointModel(virtual_joint.name_, joint_index, first_variable_index);
1021 else if (virtual_joint.type_ ==
"floating")
1023 new_joint_model =
new FloatingJointModel(virtual_joint.name_, joint_index, first_variable_index);
1025 if (new_joint_model)
1028 if (virtual_joint.type_ !=
"fixed")
1036 if (!new_joint_model)
1038 RCLCPP_INFO(
getLogger(),
"No root/virtual joint specified in SRDF. Assuming fixed joint");
1039 new_joint_model =
new FixedJointModel(
"ASSUMED_FIXED_ROOT_JOINT", joint_index, first_variable_index);
1043 if (new_joint_model)
1045 new_joint_model->setDistanceFactor(new_joint_model->getStateSpaceDimension());
1046 const std::vector<srdf::Model::PassiveJoint>& pjoints = srdf_model.getPassiveJoints();
1047 for (
const srdf::Model::PassiveJoint& pjoint : pjoints)
1049 if (new_joint_model->getName() == pjoint.name_)
1051 new_joint_model->setPassive(
true);
1056 for (
const srdf::Model::JointProperty& property : srdf_model.getJointProperties(new_joint_model->
getName()))
1058 if (property.property_name_ ==
"angular_distance_weight")
1060 double angular_distance_weight;
1063 std::string::size_type sz;
1064 angular_distance_weight = std::stod(property.value_, &sz);
1065 if (sz != property.value_.size())
1067 RCLCPP_WARN_STREAM(
getLogger(),
"Extra characters after property "
1068 << property.property_name_ <<
" for joint " << property.joint_name_
1069 <<
" as double: '" << property.value_.substr(sz) <<
'\'');
1072 catch (
const std::invalid_argument& e)
1074 RCLCPP_ERROR_STREAM(
getLogger(),
"Unable to parse property " << property.property_name_ <<
" for joint "
1075 << property.joint_name_ <<
" as double: '"
1076 << property.value_ <<
'\'');
1082 static_cast<PlanarJointModel*
>(new_joint_model)->setAngularDistanceWeight(angular_distance_weight);
1086 static_cast<FloatingJointModel*
>(new_joint_model)->setAngularDistanceWeight(angular_distance_weight);
1090 RCLCPP_ERROR_STREAM(
getLogger(),
"Cannot apply property " << property.property_name_ <<
" to joint type: "
1091 << new_joint_model->getTypeName());
1094 else if (property.property_name_ ==
"motion_model")
1098 RCLCPP_ERROR(
getLogger(),
"Cannot apply property %s to joint type: %s", property.property_name_.c_str(),
1099 new_joint_model->getTypeName().c_str());
1104 if (property.value_ ==
"holonomic")
1108 else if (property.value_ ==
"diff_drive")
1114 RCLCPP_ERROR_STREAM(
getLogger(),
"Unknown value for property " << property.property_name_ <<
" ("
1115 << property.joint_name_ <<
"): '"
1116 << property.value_ <<
'\'');
1117 RCLCPP_ERROR(
getLogger(),
"Valid values are 'holonomic' and 'diff_drive'");
1121 static_cast<PlanarJointModel*
>(new_joint_model)->setMotionModel(motion_model);
1123 else if (property.property_name_ ==
"min_translational_distance")
1127 RCLCPP_ERROR(
getLogger(),
"Cannot apply property %s to joint type: %s", property.property_name_.c_str(),
1128 new_joint_model->getTypeName().c_str());
1131 double min_translational_distance;
1134 std::string::size_type sz;
1135 min_translational_distance = std::stod(property.value_, &sz);
1136 if (sz != property.value_.size())
1138 RCLCPP_WARN_STREAM(
getLogger(),
"Extra characters after property "
1139 << property.property_name_ <<
" for joint " << property.joint_name_
1140 <<
" as double: '" << property.value_.substr(sz) <<
'\'');
1143 catch (
const std::invalid_argument& e)
1145 RCLCPP_ERROR_STREAM(
getLogger(),
"Unable to parse property " << property.property_name_ <<
" for joint "
1146 << property.joint_name_ <<
" as double: '"
1147 << property.value_ <<
'\'');
1151 static_cast<PlanarJointModel*
>(new_joint_model)->setMinTranslationalDistance(min_translational_distance);
1155 RCLCPP_ERROR(
getLogger(),
"Unknown joint property: %s", property.property_name_.c_str());
1160 return new_joint_model;
1165inline Eigen::Isometry3d urdfPose2Isometry3d(
const urdf::Pose& pose)
1167 Eigen::Quaterniond q(pose.rotation.w, pose.rotation.x, pose.rotation.y, pose.rotation.z);
1168 Eigen::Isometry3d af(Eigen::Translation3d(pose.position.x, pose.position.y, pose.position.z) * q);
1173LinkModel* RobotModel::constructLinkModel(
const urdf::Link* urdf_link)
1176 LinkModel* new_link_model =
new LinkModel(urdf_link->name, link_index);
1178 const std::vector<urdf::CollisionSharedPtr>& col_array =
1179 urdf_link->collision_array.empty() ? std::vector<urdf::CollisionSharedPtr>(1, urdf_link->collision) :
1180 urdf_link->collision_array;
1182 std::vector<shapes::ShapeConstPtr>
shapes;
1183 EigenSTL::vector_Isometry3d poses;
1185 for (
const urdf::CollisionSharedPtr& col : col_array)
1187 if (col && col->geometry)
1189 shapes::ShapeConstPtr s = constructShape(col->geometry.get());
1193 poses.push_back(urdfPose2Isometry3d(col->origin));
1199 bool warn_about_missing_collision =
false;
1202 const auto& vis_array = urdf_link->visual_array.empty() ? std::vector<urdf::VisualSharedPtr>{ urdf_link->visual } :
1203 urdf_link->visual_array;
1204 for (
const urdf::VisualSharedPtr& vis : vis_array)
1206 if (vis && vis->geometry)
1207 warn_about_missing_collision =
true;
1210 if (warn_about_missing_collision)
1213 "Link " << urdf_link->name
1214 <<
" has visual geometry but no collision geometry. "
1215 "Collision geometry will be left empty. "
1216 "Fix your URDF file by explicitly specifying collision geometry.");
1219 new_link_model->setGeometry(
shapes, poses);
1222 if (urdf_link->visual && urdf_link->visual->geometry)
1224 if (urdf_link->visual->geometry->type == urdf::Geometry::MESH)
1226 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(urdf_link->visual->geometry.get());
1227 if (!mesh->filename.empty())
1229 new_link_model->setVisualMesh(mesh->filename, urdfPose2Isometry3d(urdf_link->visual->origin),
1230 Eigen::Vector3d(mesh->scale.x, mesh->scale.y, mesh->scale.z));
1234 else if (urdf_link->collision && urdf_link->collision->geometry)
1236 if (urdf_link->collision->geometry->type == urdf::Geometry::MESH)
1238 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(urdf_link->collision->geometry.get());
1239 if (!mesh->filename.empty())
1241 new_link_model->setVisualMesh(mesh->filename, urdfPose2Isometry3d(urdf_link->collision->origin),
1242 Eigen::Vector3d(mesh->scale.x, mesh->scale.y, mesh->scale.z));
1247 if (urdf_link->parent_joint)
1249 new_link_model->setJointOriginTransform(
1250 urdfPose2Isometry3d(urdf_link->parent_joint->parent_to_joint_origin_transform));
1253 return new_link_model;
1256shapes::ShapePtr RobotModel::constructShape(
const urdf::Geometry* geom)
1258 shapes::Shape* new_shape =
nullptr;
1261 case urdf::Geometry::SPHERE:
1262 new_shape =
new shapes::Sphere(
static_cast<const urdf::Sphere*
>(geom)->radius);
1264 case urdf::Geometry::BOX:
1266 urdf::Vector3 dim =
static_cast<const urdf::Box*
>(geom)->dim;
1267 new_shape =
new shapes::Box(dim.x, dim.y, dim.z);
1270 case urdf::Geometry::CYLINDER:
1271 new_shape =
new shapes::Cylinder(
static_cast<const urdf::Cylinder*
>(geom)->radius,
1272 static_cast<const urdf::Cylinder*
>(geom)->length);
1274 case urdf::Geometry::MESH:
1276 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(geom);
1277 if (!mesh->filename.empty())
1279 Eigen::Vector3d scale(mesh->scale.x, mesh->scale.y, mesh->scale.z);
1280 shapes::Mesh* m = shapes::createMeshFromResource(mesh->filename, scale);
1286 RCLCPP_ERROR(
getLogger(),
"Unknown geometry type: %d",
static_cast<int>(geom->type));
1290 return shapes::ShapePtr(new_shape);
1308 RCLCPP_ERROR(getLogger(),
"Joint '%s' not found in model '%s'", name.c_str(),
model_name_.c_str());
1316 RCLCPP_ERROR(getLogger(),
"Joint index '%li' out of bounds of joints in model '%s'", index,
model_name_.c_str());
1328 RCLCPP_ERROR(getLogger(),
"Joint '%s' not found in model '%s'", name.c_str(),
model_name_.c_str());
1341 RCLCPP_ERROR(getLogger(),
"Link index '%li' out of bounds of links in model '%s'", index,
model_name_.c_str());
1362 RCLCPP_ERROR(getLogger(),
"Link '%s' not found in model '%s'", name.c_str(),
model_name_.c_str());
1387 int src = mimic_joint->getMimic()->getFirstVariableIndex();
1388 int dest = mimic_joint->getFirstVariableIndex();
1389 values[dest] = values[src] * mimic_joint->getMimicFactor() + mimic_joint->getMimicOffset();
1401 std::map<std::string, double>& values)
const
1427 std::vector<std::string>& missing_variables)
const
1429 missing_variables.clear();
1430 std::set<std::string> keys(variables.begin(), variables.end());
1433 if (keys.find(variable_name) == keys.end())
1436 missing_variables.push_back(variable_name);
1451 double max_distance = 0.0;
1457 return max_distance;
1461 double margin)
const
1467 *active_joint_bounds[i], margin))
1476 bool change =
false;
1480 *active_joint_bounds[i]))
1502 moveit::core::checkInterpolationParamBounds(getLogger(), t);
1519 std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->getName());
1520 if (jt != allocators.end())
1522 std::pair<SolverAllocatorFn, SolverAllocatorMapFn> solver_allocator_pair;
1523 solver_allocator_pair.first = jt->second;
1524 jmg->setSolverAllocators(solver_allocator_pair);
1532 std::pair<SolverAllocatorFn, SolverAllocatorMapFn> solver_allocator_pair;
1533 std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->getName());
1534 if (jt == allocators.end())
1537 std::set<const JointModel*> joints;
1538 joints.insert(jmg->getJointModels().begin(), jmg->getJointModels().end());
1540 std::vector<const JointModelGroup*> subs;
1543 for (
const std::pair<const std::string, SolverAllocatorFn>& allocator : allocators)
1551 std::set<const JointModel*> sub_joints;
1554 if (std::includes(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end()))
1556 std::set<const JointModel*> joint_model_set;
1557 std::set_difference(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end(),
1558 std::inserter(joint_model_set, joint_model_set.end()));
1564 subs.push_back(sub);
1565 joints.swap(joint_model_set);
1572 std::stringstream ss;
1575 ss << sub->getName() <<
' ';
1576 solver_allocator_pair.second[sub] = allocators.find(sub->getName())->second;
1578 RCLCPP_DEBUG(getLogger(),
"Added sub-group IK allocators for group '%s': [ %s]", jmg->getName().c_str(),
1581 jmg->setSolverAllocators(solver_allocator_pair);
1590 std::ios_base::fmtflags old_flags = out.flags();
1591 out.setf(std::ios::fixed, std::ios::floatfield);
1592 std::streamsize old_prec = out.precision();
1594 out <<
"Joints: \n";
1597 out <<
" '" << joint_model->getName() <<
"' (" << joint_model->getTypeName() <<
")\n";
1598 out <<
" * Joint Index: " << joint_model->getJointIndex() <<
'\n';
1599 const std::vector<std::string>& vn = joint_model->getVariableNames();
1600 out <<
" * " << vn.size() << (vn.size() > 1 ?
" variables:" : (vn.empty() ?
" variables" :
" variable:\n"));
1601 int idx = joint_model->getFirstVariableIndex();
1602 for (
const std::string& it : vn)
1604 out <<
" * '" << it <<
"', index " << idx++ <<
" in full state";
1605 if (joint_model->getMimic())
1606 out <<
", mimic '" << joint_model->getMimic()->getName() <<
'\'';
1607 if (joint_model->isPassive())
1610 out <<
" " << joint_model->getVariableBounds(it) <<
'\n';
1614 out.precision(old_prec);
1615 out.flags(old_flags);
1619 out <<
" '" << link_model->getName() <<
"' with " << link_model->getShapes().size() <<
" geoms\n";
1620 if (link_model->parentJointIsFixed())
1623 <<
"parent joint is fixed" <<
'\n';
1625 if (link_model->jointOriginTransformIsIdentity())
1628 <<
"joint origin transform is identity\n";
1632 out <<
"Available groups: \n";
1634 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 * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
const JointModel * getMimic() const
Get the joint this one is mimicking.
JointType getType() const
Get the type of joint.
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
A link from the robot. Contains the constant transform applied to the link and its geometry.
const std::string & getName() const
The name of this link.
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
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 Eigen::Isometry3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link's origin....
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::string & getName() const
Get the model name.
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.
const JointModel * getJointOfVariable(int variable_index) const
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.
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 std::vector< const JointModel * > & getJointModels() const
Get the array of joints, in the order they appear in the robot state.
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.
bool enforcePositionBounds(double *state) const
rclcpp::Logger getLogger()
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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
FilterFn chain(const std::vector< FilterFn > &filter_functions)