40 #include <boost/math/constants/constants.hpp>
46 #include "order_robot_model_items.inc"
54 constexpr
char LOGNAME[] =
"robot_model";
97 if (urdf_model.getRoot())
99 const urdf::Link* root_link_ptr = urdf_model.getRoot().get();
132 typedef std::map<const JointModel*, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
133 std::set<const JointModel*, OrderJointsByIndex>>>
136 void computeDescendantsHelper(
const JointModel* joint, std::vector<const JointModel*>& parents,
137 std::set<const JointModel*>& seen, DescMap& descendants)
141 if (seen.find(joint) != seen.end())
146 descendants[parent].second.insert(joint);
153 descendants[parent].first.insert(lm);
154 descendants[joint].first.insert(lm);
156 parents.push_back(joint);
158 for (
const JointModel* child_joint_model : ch)
159 computeDescendantsHelper(child_joint_model, parents, seen, descendants);
161 for (
const JointModel* mimic_joint_model : mim)
162 computeDescendantsHelper(mimic_joint_model, parents, seen, descendants);
166 void computeCommonRootsHelper(
const JointModel* joint, std::vector<int>& common_roots,
int size)
175 for (std::size_t i = 0; i < ch.size(); ++i)
177 const std::vector<const JointModel*>& a = ch[i]->getDescendantJointModels();
178 for (std::size_t j = i + 1; j < ch.size(); ++j)
180 const std::vector<const JointModel*>& b = ch[j]->getDescendantJointModels();
182 common_roots[ch[i]->getJointIndex() * size + m->getJointIndex()] =
183 common_roots[ch[i]->getJointIndex() + m->getJointIndex() * size] = joint->
getJointIndex();
186 common_roots[k->getJointIndex() * size + ch[j]->getJointIndex()] =
187 common_roots[k->getJointIndex() + ch[j]->getJointIndex() * size] = joint->
getJointIndex();
189 common_roots[k->getJointIndex() * size + m->getJointIndex()] =
190 common_roots[k->getJointIndex() + m->getJointIndex() * size] = joint->
getJointIndex();
193 computeCommonRootsHelper(ch[i], common_roots, size);
220 const std::vector<const JointModel*>&
d = joint_model->getDescendantJointModels();
221 for (
const JointModel* descendant_joint_model :
d)
223 joint_model->getJointIndex()] =
232 std::vector<const JointModel*> parents;
233 std::set<const JointModel*> seen;
236 computeDescendantsHelper(
root_joint_, parents, seen, descendants);
237 for (std::pair<
const JointModel*
const, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
238 std::set<const JointModel*, OrderJointsByIndex>>>& descendant :
241 JointModel* jm =
const_cast<JointModel*
>(descendant.first);
242 for (
const JointModel* jt : descendant.second.second)
243 jm->addDescendantJointModel(jt);
244 for (
const LinkModel* jt : descendant.second.first)
245 jm->addDescendantLinkModel(jt);
266 if (!name_order.empty())
268 for (std::size_t j = 0; j < name_order.size(); ++j)
303 if (link_considered[link->getLinkIndex()])
308 for (
auto& tf_base : associated_transforms)
310 link_considered[tf_base.first->getLinkIndex()] =
true;
311 for (
auto& tf_target : associated_transforms)
313 if (&tf_base != &tf_target)
314 const_cast<LinkModel*
>(tf_base.first)
315 ->addAssociatedFixedTransform(tf_target.first, tf_base.second.inverse() * tf_target.second);
327 const std::vector<srdf::Model::GroupState>& ds = srdf_model.
getGroupStates();
333 std::vector<const JointModel*> remaining_joints = jmg->getActiveJointModels();
334 std::map<std::string, double> state;
335 for (std::map<std::string, std::vector<double>>::const_iterator jt = group_state.joint_values_.begin();
336 jt != group_state.joint_values_.end(); ++jt)
338 if (jmg->hasJointModel(jt->first))
340 const JointModel* jm = jmg->getJointModel(jt->first);
341 const std::vector<std::string>& vn = jm->getVariableNames();
343 auto it_found = std::find(remaining_joints.begin(), remaining_joints.end(), jm);
344 if (it_found != remaining_joints.end())
345 remaining_joints.erase(it_found);
346 if (vn.size() == jt->second.size())
347 for (std::size_t j = 0; j < vn.size(); ++j)
348 state[vn[j]] = jt->second[j];
351 "The model for joint '%s' requires %d variable values, "
352 "but only %d variable values were supplied in default state '%s' for group '%s'",
353 jt->first.c_str(), (
int)vn.size(), (
int)jt->second.size(), group_state.name_.c_str(),
354 jmg->getName().c_str());
358 "Group state '%s' specifies value for joint '%s', "
359 "but that joint is not part of group '%s'",
360 group_state.name_.c_str(), jt->first.c_str(), jmg->getName().c_str());
362 if (!remaining_joints.empty())
364 std::stringstream missing;
365 missing << (*remaining_joints.begin())->
getName();
366 for (
auto j = ++remaining_joints.begin(); j != remaining_joints.end(); j++)
368 missing <<
", " << (*j)->getName();
371 <<
"' doesn't specify all group joints in group '"
372 << group_state.group_ <<
"'. " << missing.str() <<
" "
373 << (remaining_joints.size() > 1 ?
"are" :
"is") <<
" missing.");
376 jmg->addDefaultState(group_state.name_, state);
380 group_state.name_.c_str(), group_state.group_.c_str());
389 const urdf::Joint* jm = urdf_model.getJoint(joint_model->getName()).get();
393 JointModelMap::const_iterator jit =
joint_model_map_.find(jm->mimic->joint_name);
396 if (joint_model->getVariableCount() == jit->second->getVariableCount())
397 joint_model->setMimic(jit->second, jm->mimic->multiplier, jm->mimic->offset);
400 joint_model->getName().c_str(), jm->mimic->joint_name.c_str());
404 jm->mimic->joint_name.c_str());
414 if (joint_model->getMimic())
416 if (joint_model->getMimic()->getMimic())
418 joint_model->setMimic(joint_model->getMimic()->getMimic(),
419 joint_model->getMimicFactor() * joint_model->getMimic()->getMimicFactor(),
420 joint_model->getMimicOffset() +
421 joint_model->getMimicFactor() * joint_model->getMimic()->getMimicOffset());
424 if (joint_model == joint_model->getMimic())
428 joint_model_recal->setMimic(
nullptr, 0.0, 0.0);
436 if (joint_model->getMimic())
438 const_cast<JointModel*
>(joint_model->getMimic())->addMimicRequest(joint_model);
505 const std::vector<srdf::Model::Group>& group_configs = srdf_model.
getGroups();
508 std::vector<bool> processed(group_configs.size(),
false);
516 for (std::size_t i = 0; i < group_configs.size(); ++i)
520 bool all_subgroups_added =
true;
521 for (
const std::string& subgroup : group_configs[i].subgroups_)
524 all_subgroups_added =
false;
527 if (all_subgroups_added)
537 for (std::size_t i = 0; i < processed.size(); ++i)
540 group_configs[i].name_.c_str());
561 std::vector<std::string> subgroup_names;
565 if (jt->first != it->first)
570 for (
const JointModel* sub_joint : sub_joints)
571 if (joints.find(sub_joint) == joints.end())
577 subgroup_names.push_back(sub_jmg->
getName());
579 if (!subgroup_names.empty())
587 const std::vector<srdf::Model::EndEffector>& eefs = srdf_model.
getEndEffectors();
592 if (eef.component_group_ == it->first)
595 it->second->setEndEffectorName(eef.name_);
601 std::vector<JointModelGroup*> possible_parent_groups;
604 if (jt->first != it->first)
606 if (jt->second->hasLinkModel(eef.parent_link_))
608 jt->second->attachEndEffector(eef.name_);
609 possible_parent_groups.push_back(jt->second);
613 JointModelGroup* eef_parent_group =
nullptr;
615 if (!eef.parent_group_.empty())
620 if (jt->second->hasLinkModel(eef.parent_link_))
622 if (jt->second != it->second)
623 eef_parent_group = jt->second;
626 eef.parent_group_.c_str(), eef.name_.c_str());
630 "Group '%s' was specified as parent group for end-effector '%s' "
631 "but it does not include the parent link '%s'",
632 eef.parent_group_.c_str(), eef.name_.c_str(), eef.parent_link_.c_str());
636 eef.parent_group_.c_str(), eef.name_.c_str());
640 if (eef_parent_group ==
nullptr)
641 if (!possible_parent_groups.empty())
645 std::size_t best = 0;
646 for (std::size_t g = 1; g < possible_parent_groups.size(); ++g)
650 eef_parent_group = possible_parent_groups[best];
653 if (eef_parent_group)
655 it->second->setEndEffectorParent(eef_parent_group->getName(), eef.parent_link_);
660 it->second->setEndEffectorParent(
"", eef.parent_link_);
675 std::set<const JointModel*> jset;
678 for (
const std::pair<std::string, std::string>& chain : gc.
chains_)
682 if (base_link && tip_link)
685 const LinkModel* lm = tip_link;
686 std::vector<const JointModel*> cj;
691 cj.push_back(lm->getParentJointModel());
700 std::size_t
index = 0;
701 std::vector<const JointModel*> cj2;
704 for (std::size_t j = 0; j < cj.size(); ++j)
705 if (cj[j] == lm->getParentJointModel())
712 cj2.push_back(lm->getParentJointModel());
713 lm = lm->getParentJointModel()->getParentLinkModel();
717 jset.insert(cj.begin(), cj.begin() + index);
718 jset.insert(cj2.begin(), cj2.end());
723 jset.insert(cj.begin(), cj.end());
728 for (
const std::string& joint : gc.
joints_)
736 for (
const std::string& link : gc.
links_)
744 for (
const std::string& subgroup : gc.
subgroups_)
750 const std::vector<const JointModel*>& js = sg->getJointModels();
751 for (
const JointModel* j : js)
755 const std::vector<const JointModel*>& fs = sg->getFixedJointModels();
756 for (
const JointModel* f : fs)
760 const std::vector<const JointModel*>& ms = sg->getMimicJointModels();
761 for (
const JointModel* m : ms)
772 std::vector<const JointModel*> joints;
773 joints.reserve(jset.size());
774 for (
const JointModel* it : jset)
775 joints.push_back(it);
777 JointModelGroup* jmg =
new JointModelGroup(gc.
name_, gc, joints,
this);
786 JointModel* joint = urdf_link->parent_joint ?
789 if (joint ==
nullptr)
798 joint->setParentLinkModel(parent);
802 joint->setChildLinkModel(link);
803 link->setParentLinkModel(parent);
811 if (!link->getShapes().empty())
818 link->setParentJointModel(joint);
821 for (
unsigned int i = 0; i < urdf_link->child_links.size(); ++i)
823 const urdf::LinkSharedPtr& child_link{ urdf_link->child_links[i] };
824 const urdf::JointSharedPtr& child_joint{ urdf_link->child_joints[i] };
826 if (child_link->parent_joint->name != child_joint->name)
829 << child_link->parent_joint->name <<
"' and '" << child_joint->name
830 <<
"'. Ignoring the latter joint because cycles in the kinematic "
831 "structure are not supported.");
835 JointModel* jm =
buildRecursive(link, child_link.get(), srdf_model);
837 link->addChildJointModel(jm);
845 static inline VariableBounds jointBoundsFromURDF(
const urdf::Joint* urdf_joint)
848 if (urdf_joint->safety)
850 b.position_bounded_ =
true;
851 b.min_position_ = urdf_joint->safety->soft_lower_limit;
852 b.max_position_ = urdf_joint->safety->soft_upper_limit;
853 if (urdf_joint->limits)
855 if (urdf_joint->limits->lower > b.min_position_)
856 b.min_position_ = urdf_joint->limits->lower;
857 if (urdf_joint->limits->upper < b.max_position_)
858 b.max_position_ = urdf_joint->limits->upper;
863 if (urdf_joint->limits)
865 b.position_bounded_ =
true;
866 b.min_position_ = urdf_joint->limits->lower;
867 b.max_position_ = urdf_joint->limits->upper;
870 if (urdf_joint->limits)
872 b.max_velocity_ = fabs(urdf_joint->limits->velocity);
873 b.min_velocity_ = -b.max_velocity_;
874 b.velocity_bounded_ = b.max_velocity_ > std::numeric_limits<double>::epsilon();
883 JointModel* new_joint_model =
nullptr;
888 switch (urdf_joint->type)
890 case urdf::Joint::REVOLUTE:
892 RevoluteJointModel* j =
new RevoluteJointModel(urdf_joint->name);
893 j->setVariableBounds(j->getName(), jointBoundsFromURDF(urdf_joint));
894 j->setContinuous(
false);
895 j->setAxis(
Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z));
899 case urdf::Joint::CONTINUOUS:
901 RevoluteJointModel* j =
new RevoluteJointModel(urdf_joint->name);
902 j->setVariableBounds(j->getName(), jointBoundsFromURDF(urdf_joint));
903 j->setContinuous(
true);
904 j->setAxis(
Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z));
908 case urdf::Joint::PRISMATIC:
910 PrismaticJointModel* j =
new PrismaticJointModel(urdf_joint->name);
911 j->setVariableBounds(j->getName(), jointBoundsFromURDF(urdf_joint));
912 j->setAxis(
Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z));
916 case urdf::Joint::FLOATING:
917 new_joint_model =
new FloatingJointModel(urdf_joint->name);
919 case urdf::Joint::PLANAR:
920 new_joint_model =
new PlanarJointModel(urdf_joint->name);
922 case urdf::Joint::FIXED:
923 new_joint_model =
new FixedJointModel(urdf_joint->name);
932 const std::vector<srdf::Model::VirtualJoint>& virtual_joints = srdf_model.
getVirtualJoints();
935 if (virtual_joint.child_link_ != child_link->name)
937 if (child_link->name ==
"world" && virtual_joint.type_ ==
"fixed" && child_link->collision_array.empty() &&
938 !child_link->collision && child_link->visual_array.empty() && !child_link->visual)
941 new_joint_model =
new FixedJointModel(virtual_joint.name_);
944 "Skipping virtual joint '%s' because its child frame '%s' "
945 "does not match the URDF frame '%s'",
946 virtual_joint.name_.c_str(), virtual_joint.child_link_.c_str(), child_link->name.c_str());
948 else if (virtual_joint.parent_frame_.empty())
951 virtual_joint.name_.c_str());
955 if (virtual_joint.type_ ==
"fixed")
956 new_joint_model =
new FixedJointModel(virtual_joint.name_);
957 else if (virtual_joint.type_ ==
"planar")
958 new_joint_model =
new PlanarJointModel(virtual_joint.name_);
959 else if (virtual_joint.type_ ==
"floating")
960 new_joint_model =
new FloatingJointModel(virtual_joint.name_);
964 if (virtual_joint.type_ !=
"fixed")
972 if (!new_joint_model)
975 new_joint_model =
new FixedJointModel(
"ASSUMED_FIXED_ROOT_JOINT");
981 new_joint_model->setDistanceFactor(new_joint_model->getStateSpaceDimension());
982 const std::vector<srdf::Model::PassiveJoint>& pjoints = srdf_model.
getPassiveJoints();
983 const std::string& joint_name = new_joint_model->getName();
986 if (joint_name == pjoint.name_)
988 new_joint_model->setPassive(
true);
997 auto parse_property_double = [&joint_name](
auto& prop_name,
auto& prop_value_str,
double& prop_value) ->
bool {
1003 catch (
const std::runtime_error& e)
1006 <<
" as double: '" << prop_value_str <<
"'");
1011 for (
const auto& [property_name, property_value_str] : srdf_model.
getJointProperties(joint_name))
1013 if (property_name ==
"angular_distance_weight")
1015 double angular_distance_weight;
1016 if (parse_property_double(property_name, property_value_str, angular_distance_weight))
1018 if (new_joint_model->getType() == JointModel::JointType::PLANAR)
1020 ((PlanarJointModel*)new_joint_model)->setAngularDistanceWeight(angular_distance_weight);
1022 else if (new_joint_model->getType() == JointModel::JointType::FLOATING)
1024 ((FloatingJointModel*)new_joint_model)->setAngularDistanceWeight(angular_distance_weight);
1029 new_joint_model->getTypeName().c_str());
1033 else if (property_name ==
"motion_model")
1035 if (new_joint_model->getType() != JointModel::JointType::PLANAR)
1038 new_joint_model->getTypeName().c_str());
1043 if (property_value_str ==
"holonomic")
1045 motion_model = PlanarJointModel::MotionModel::HOLONOMIC;
1047 else if (property_value_str ==
"diff_drive")
1049 motion_model = PlanarJointModel::MotionModel::DIFF_DRIVE;
1054 << property_value_str <<
"'");
1059 ((PlanarJointModel*)new_joint_model)->setMotionModel(motion_model);
1061 else if (property_name ==
"min_translational_distance")
1063 if (new_joint_model->getType() != JointModel::JointType::PLANAR)
1066 new_joint_model->getTypeName().c_str());
1069 double min_translational_distance;
1070 if (parse_property_double(property_name, property_value_str, min_translational_distance))
1072 ((PlanarJointModel*)new_joint_model)->setMinTranslationalDistance(min_translational_distance);
1082 return new_joint_model;
1087 static inline Eigen::Isometry3d urdfPose2Isometry3d(
const urdf::Pose& pose)
1089 Eigen::Quaterniond q(pose.rotation.w, pose.rotation.x, pose.rotation.y, pose.rotation.z);
1090 Eigen::Isometry3d af(Eigen::Translation3d(pose.position.x, pose.position.y, pose.position.z) * q);
1097 LinkModel* new_link_model =
new LinkModel(urdf_link->name);
1099 const std::vector<urdf::CollisionSharedPtr>& col_array =
1100 urdf_link->collision_array.empty() ? std::vector<urdf::CollisionSharedPtr>(1, urdf_link->collision) :
1101 urdf_link->collision_array;
1103 std::vector<shapes::ShapeConstPtr>
shapes;
1106 for (
const urdf::CollisionSharedPtr& col : col_array)
1108 if (col && col->geometry)
1114 poses.push_back(urdfPose2Isometry3d(col->origin));
1120 bool warn_about_missing_collision =
false;
1123 const auto& vis_array = urdf_link->visual_array.empty() ? std::vector<urdf::VisualSharedPtr>{ urdf_link->visual } :
1124 urdf_link->visual_array;
1125 for (
const urdf::VisualSharedPtr& vis : vis_array)
1127 if (vis && vis->geometry)
1128 warn_about_missing_collision =
true;
1131 if (warn_about_missing_collision)
1134 "Link " << urdf_link->name
1135 <<
" has visual geometry but no collision geometry. "
1136 "Collision geometry will be left empty. "
1137 "Fix your URDF file by explicitly specifying collision geometry.");
1140 new_link_model->setGeometry(
shapes, poses);
1143 if (urdf_link->visual && urdf_link->visual->geometry)
1145 if (urdf_link->visual->geometry->type == urdf::Geometry::MESH)
1147 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(urdf_link->visual->geometry.get());
1148 if (!mesh->filename.empty())
1149 new_link_model->setVisualMesh(mesh->filename, urdfPose2Isometry3d(urdf_link->visual->origin),
1153 else if (urdf_link->collision && urdf_link->collision->geometry)
1155 if (urdf_link->collision->geometry->type == urdf::Geometry::MESH)
1157 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(urdf_link->collision->geometry.get());
1158 if (!mesh->filename.empty())
1159 new_link_model->setVisualMesh(mesh->filename, urdfPose2Isometry3d(urdf_link->collision->origin),
1164 if (urdf_link->parent_joint)
1165 new_link_model->setJointOriginTransform(
1166 urdfPose2Isometry3d(urdf_link->parent_joint->parent_to_joint_origin_transform));
1168 return new_link_model;
1178 case urdf::Geometry::SPHERE:
1179 new_shape =
new shapes::Sphere(
static_cast<const urdf::Sphere*
>(geom)->radius);
1181 case urdf::Geometry::BOX:
1183 urdf::Vector3 dim =
static_cast<const urdf::Box*
>(geom)->dim;
1187 case urdf::Geometry::CYLINDER:
1188 new_shape =
new shapes::Cylinder(
static_cast<const urdf::Cylinder*
>(geom)->radius,
1189 static_cast<const urdf::Cylinder*
>(geom)->length);
1191 case urdf::Geometry::MESH:
1193 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(geom);
1194 if (!mesh->filename.empty())
1300 std::find(begin, end, joint) == end)
1305 while (parent_link && is_fixed_or_not_in_jmg(joint))
1319 int src = mimic_joint->getMimic()->getFirstVariableIndex();
1320 int dest = mimic_joint->getFirstVariableIndex();
1321 values[dest] =
values[src] * mimic_joint->getMimicFactor() + mimic_joint->getMimicOffset();
1333 std::map<std::string, double>& values)
const
1359 std::vector<std::string>& missing_variables)
const
1361 missing_variables.clear();
1362 std::set<std::string> keys(variables.begin(), variables.end());
1364 if (keys.find(variable_name) == keys.end())
1366 missing_variables.push_back(variable_name);
1373 throw Exception(
"Variable '" + variable +
"' is not known to model '" +
model_name_ +
"'");
1379 double max_distance = 0.0;
1383 return max_distance;
1387 double margin)
const
1392 *active_joint_bounds[i], margin))
1400 bool change =
false;
1403 *active_joint_bounds[i]))
1437 std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->
getName());
1438 if (jt != allocators.end())
1440 std::pair<SolverAllocatorFn, SolverAllocatorMapFn> solver_allocator_pair;
1441 solver_allocator_pair.first = jt->second;
1450 std::pair<SolverAllocatorFn, SolverAllocatorMapFn> solver_allocator_pair;
1451 std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->
getName());
1452 if (jt == allocators.end())
1455 std::set<const JointModel*> joints;
1458 std::vector<const JointModelGroup*> subs;
1461 for (
const std::pair<const std::string, SolverAllocatorFn>& allocator : allocators)
1469 std::set<const JointModel*> sub_joints;
1472 if (std::includes(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end()))
1474 std::set<const JointModel*> joint_model_set;
1475 std::set_difference(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end(),
1476 std::inserter(joint_model_set, joint_model_set.end()));
1482 subs.push_back(sub);
1483 joints.swap(joint_model_set);
1490 std::stringstream ss;
1494 solver_allocator_pair.second[sub] = allocators.find(sub->
getName())->second;
1509 std::ios_base::fmtflags old_flags = out.flags();
1510 out.setf(std::ios::fixed, std::ios::floatfield);
1511 std::streamsize old_prec = out.precision();
1513 out <<
"Joints: " << std::endl;
1516 out <<
" '" << joint_model->getName() <<
"' (" << joint_model->getTypeName() <<
")" << std::endl;
1517 out <<
" * Joint Index: " << joint_model->getJointIndex() << std::endl;
1518 const std::vector<std::string>& vn = joint_model->getVariableNames();
1519 out <<
" * " << vn.size() << (vn.size() > 1 ?
" variables:" : (vn.empty() ?
" variables" :
" variable:"))
1521 int idx = joint_model->getFirstVariableIndex();
1522 for (
const std::string& it : vn)
1524 out <<
" * '" << it <<
"', index " << idx++ <<
" in full state";
1525 if (joint_model->getMimic())
1526 out <<
", mimic '" << joint_model->getMimic()->getName() <<
"'";
1527 if (joint_model->isPassive())
1530 out <<
" " << joint_model->getVariableBounds(it) << std::endl;
1534 out.precision(old_prec);
1535 out.flags(old_flags);
1536 out <<
"Links: " << std::endl;
1539 out <<
" '" << link_model->getName() <<
"' with " << link_model->getShapes().size() <<
" geoms" << std::endl;
1540 if (link_model->parentJointIsFixed())
1542 <<
"parent joint is fixed" << std::endl;
1543 if (link_model->jointOriginTransformIsIdentity())
1545 <<
"joint origin transform is identity" << std::endl;
1548 out <<
"Available groups: " << std::endl;
1550 joint_model_group->printGroupInfo(out);
1556 associated_transforms[link] =
transform * link->getJointOriginTransform();
1557 for (std::size_t i = 0; i < link->getChildJointModels().size(); ++i)
1560 transform * link->getJointOriginTransform(), associated_transforms);