16 typedef pinocchio::urdf::details::
17 UrdfVisitor<double, 0, ::pinocchio::JointCollectionDefaultTpl>
21 static const std::array<std::string, 3>
ELEMENTS = {
"joint",
"geom",
"site"};
29 dst.put(ptree::path_type(
v.first),
v.second.data());
37 for (
const std::string & el :
ELEMENTS)
39 std::string
path = el +
".<xmlattr>";
44 const ptree & attr_current = current.get_child(
path, default_value);
49 current.put_child(
path, attr_parent);
56 auto n = el.get_optional<std::string>(
"<xmlattr>.name");
61 if (filePath.extension().empty())
62 throw std::invalid_argument(
"Cannot find extension for one of the mesh/texture");
64 auto st = filePath.stem();
68 throw std::invalid_argument(
"Cannot find a name for one of the mesh.texture");
74 const std::string & dir,
75 const std::string & modelPath,
78 namespace fs = boost::filesystem;
81 if (filePath.is_absolute() && !strippath)
90 if (meshPath.is_absolute())
95 return (mainPath.parent_path() / meshPath /
filename);
107 Eigen::Matrix3d aa1 =
109 Eigen::Matrix3d aa2 =
111 Eigen::Matrix3d aa3 =
114 return aa1 * aa2 * aa3;
117 template<
int Nq,
int Nv>
120 typedef UrdfVisitor::Vector Vector;
121 const double infty = std::numeric_limits<double>::infinity();
124 ret.
maxEffort = Vector::Constant(Nv, infty);
125 ret.
maxVel = Vector::Constant(Nv, infty);
126 ret.
maxConfig = Vector::Constant(Nq, 1.01);
127 ret.
minConfig = Vector::Constant(Nq, -1.01);
128 ret.
friction = Vector::Constant(Nv, 0.);
129 ret.
damping = Vector::Constant(Nv, 0.);
137 template<
int Nq,
int Nv>
174 if (!use_limits && el.get_optional<std::string>(
"<xmlattr>.range"))
175 throw std::invalid_argument(
"Range limit is specified but it was not specify to use it.");
178 auto type_s = el.get_optional<std::string>(
"<xmlattr>.type");
183 auto ax = el.get_optional<std::string>(
"<xmlattr>.axis");
185 axis = internal::getVectorFromStream<3>(*
ax);
188 auto range_ = el.get_optional<std::string>(
"<xmlattr>.range");
191 Eigen::Vector2d rangeT = internal::getVectorFromStream<2>(*range_);
196 range_ = el.get_optional<std::string>(
"<xmlattr>.actuatorfrcrange");
199 Eigen::Vector2d rangeT = internal::getVectorFromStream<2>(*range_);
204 auto value = el.get_optional<
double>(
"<xmlattr>.springref");
209 value = el.get_optional<
double>(
"<xmlattr>.damping");
213 value = el.get_optional<
double>(
"<xmlattr>.armature");
218 value = el.get_optional<
double>(
"<xmlattr>.frictionloss");
222 value = el.get_optional<
double>(
"<xmlattr>.ref");
230 throw std::invalid_argument(
231 "Reference position can only be used with hinge or slide joints.");
238 bool use_limit =
true;
240 auto name_s = el.get_optional<std::string>(
"<xmlattr>.name");
251 auto use_ls = el.get_optional<std::string>(
"<xmlattr>.limited");
252 use_limit = *use_ls ==
"true";
262 if (
auto joint_p = classD.
classElement.get_child_optional(
"joint"))
269 if (
auto joint_p = classE.
classElement.get_child_optional(
"joint"))
273 auto cl_s = el.get_optional<std::string>(
"<xmlattr>.class");
276 std::string className = *cl_s;
278 if (
auto joint_p = classE.
classElement.get_child_optional(
"joint"))
291 auto pos = el.get_optional<std::string>(
"<xmlattr>.pos");
293 placement.translation() = internal::getVectorFromStream<3>(*
pos);
297 auto rot_s = el.get_optional<std::string>(
"<xmlattr>.quat");
300 Eigen::Vector4d
quat = internal::getVectorFromStream<4>(*rot_s);
303 quaternion.normalize();
304 placement.rotation() = quaternion.toRotationMatrix();
307 else if ((rot_s = el.get_optional<std::string>(
"<xmlattr>.axisangle")))
309 Eigen::Vector4d axis_angle = internal::getVectorFromStream<4>(*rot_s);
311 double angle = axis_angle(3);
314 placement.rotation() = angleAxis.toRotationMatrix();
317 else if ((rot_s = el.get_optional<std::string>(
"<xmlattr>.euler")))
319 Eigen::Vector3d angles = internal::getVectorFromStream<3>(*rot_s);
323 else if ((rot_s = el.get_optional<std::string>(
"<xmlattr>.xyaxes")))
325 Eigen::Matrix<double, 6, 1> xyaxes = internal::getVectorFromStream<6>(*rot_s);
327 Eigen::Vector3d xAxis = xyaxes.head(3);
329 Eigen::Vector3d yAxis = xyaxes.tail(3);
332 double d = xAxis.dot(yAxis);
336 Eigen::Vector3d zAxis = xAxis.cross(yAxis);
346 else if ((rot_s = el.get_optional<std::string>(
"<xmlattr>.zaxis")))
348 Eigen::Vector3d zaxis = internal::getVectorFromStream<3>(*rot_s);
351 Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitZ(), zaxis).toRotationMatrix();
361 throw std::invalid_argument(
"Mass of body is not supposed to be negative");
364 auto com_s = el.get_optional<std::string>(
"<xmlattr>.pos");
366 com = internal::getVectorFromStream<3>(*com_s);
368 com = Inertia::Vector3::Zero();
372 Inertia::Matrix3 I = Eigen::Matrix3d::Identity();
374 auto inertia_s = el.get_optional<std::string>(
"<xmlattr>.diaginertia");
377 Eigen::Vector3d inertiaDiag = internal::getVectorFromStream<3>(*inertia_s);
378 I = inertiaDiag.asDiagonal();
381 else if ((inertia_s = el.get_optional<std::string>(
"<xmlattr>.fullinertia")))
385 inertiaStream >> I(0, 0);
386 inertiaStream >> I(1, 1);
387 inertiaStream >> I(2, 2);
388 inertiaStream >> I(0, 1);
389 inertiaStream >> I(0, 2);
390 inertiaStream >> I(1, 2);
398 for (
int i = 0;
i < 3;
i++)
406 const boost::optional<std::string> & childClass,
407 const std::string & parentName)
410 auto chcl_s = childClass;
413 throw std::invalid_argument(
"Cannot get inertia from geom and no inertia was found");
415 bool usegeominertia =
false;
417 usegeominertia =
true;
420 usegeominertia =
true;
425 if (
v.first ==
"<xmlattr>")
428 auto name_s =
v.second.get_optional<std::string>(
"name");
432 currentBody.
bodyName = parentName +
"Bis";
439 if (
auto chcl_st =
v.second.get_optional<std::string>(
"childclass"))
448 auto cl_s =
v.second.get_optional<std::string>(
"class");
455 if (
v.first ==
"inertial" && !usegeominertia)
459 if (
v.first ==
"geom")
462 currentGeom.
fill(
v.second, currentBody, *
this);
467 if (
v.first ==
"joint")
470 currentJoint.
fill(
v.second, currentBody, *
this);
473 if (
v.first ==
"freejoint")
477 auto jointName =
v.second.get_optional<std::string>(
"<xmlattr>.name");
485 if (
v.first ==
"site")
488 currentSite.
fill(
v.second, currentBody, *
this);
491 if (
v.first ==
"body")
503 inert_temp += geom.geomPlacement.act(geom.geomInertia);
512 namespace fs = boost::filesystem;
514 auto file = el.get_optional<std::string>(
"<xmlattr>.file");
515 auto name_ = el.get_optional<std::string>(
"<xmlattr>.name");
516 auto type = el.get_optional<std::string>(
"<xmlattr>.type");
525 std::cout <<
"Warning - Only texture with files are supported" << std::endl;
527 throw std::invalid_argument(
"Textures need a name.");
538 auto str_v = el.get_optional<std::string>(
"<xmlattr>.type");
542 if ((str_v = el.get_optional<std::string>(
"<xmlattr>.gridsize")))
543 text.
gridsize = internal::getVectorFromStream<2>(*str_v);
552 auto n = el.get_optional<std::string>(
"<xmlattr>.name");
556 throw std::invalid_argument(
"Material was given without a name");
562 if (
auto mat_p = classD.
classElement.get_child_optional(
"material"))
563 mat.goThroughElement(*mat_p);
565 auto cl_s = el.get_optional<std::string>(
"<xmlattr>.class");
568 std::string className = *cl_s;
570 if (
auto mat_p = classE.
classElement.get_child_optional(
"material"))
571 mat.goThroughElement(*mat_p);
574 mat.goThroughElement(el);
581 namespace fs = boost::filesystem;
584 auto file = el.get_optional<std::string>(
"<xmlattr>.file");
586 throw std::invalid_argument(
"Only meshes with files are supported");
594 auto scale = el.get_optional<std::string>(
"<xmlattr>.scale");
596 mesh.scale = internal::getVectorFromStream<3>(*scale);
605 if (
v.first ==
"mesh")
608 if (
v.first ==
"material")
611 if (
v.first ==
"texture")
614 if (
v.first ==
"hfield")
615 throw std::invalid_argument(
"hfields are not supported yet");
621 boost::optional<std::string> nameClass;
625 if (
v.first ==
"<xmlattr>")
627 nameClass =
v.second.get_optional<std::string>(
"class");
634 mapOfClasses.insert(std::make_pair(*nameClass, classDefault));
637 throw std::invalid_argument(
"Class does not have a name. Cannot parse model.");
639 else if (
v.first ==
"default")
641 else if (parentTag ==
"mujoco" &&
v.first !=
"<xmlattr>")
644 classDefault.
className =
"mujoco_default";
646 mapOfClasses.insert(std::make_pair(
"mujoco_default", classDefault));
654 auto auto_s = el.get_optional<std::string>(
"<xmlattr>.autolimits");
656 if (*auto_s ==
"true")
660 auto strip_s = el.get_optional<std::string>(
"<xmlattr>.strippath");
662 if (*strip_s ==
"true")
666 auto dir = el.get_optional<std::string>(
"<xmlattr>.assetdir");
673 if ((dir = el.get_optional<std::string>(
"<xmlattr>.meshdir")))
676 if ((dir = el.get_optional<std::string>(
"<xmlattr>.texturedir")))
679 auto value_v = el.get_optional<
double>(
"<xmlattr>.boundmass");
683 if ((value_v = el.get_optional<
double>(
"<xmlattr>.boundinertia")))
686 auto in_g = el.get_optional<std::string>(
"<xmlattr>.inertiafromgeom");
691 else if (*in_g ==
"false")
696 auto angle_s = el.get_optional<std::string>(
"<xmlattr>.angle");
698 if (*angle_s ==
"radian")
701 auto eulerS = el.get_optional<std::string>(
"<xmlattr>.eulerseq");
704 std::string eulerseq = *eulerS;
705 if (eulerseq.find_first_not_of(
"xyzXYZ") != std::string::npos || eulerseq.size() != 3)
706 throw std::invalid_argument(
707 "Model tried to use euler angles but euler sequence is wrong");
711 for (std::size_t
i = 0;
i < eulerseq.size();
i++)
735 throw std::invalid_argument(
"Euler Axis does not exist");
747 if (
v.first ==
"key")
749 auto nameKey =
v.second.get_optional<std::string>(
"<xmlattr>.name");
752 auto configVectorS =
v.second.get_optional<std::string>(
"<xmlattr>.qpos");
755 Eigen::VectorXd configVector =
757 mapOfConfigs.insert(std::make_pair(*nameKey, configVector));
768 std::string
type =
v.first;
774 if (
type !=
"connect")
784 auto body1 =
v.second.get_optional<std::string>(
"<xmlattr>.body1");
788 throw std::invalid_argument(
"Equality constraint needs a first body");
791 auto body2 =
v.second.get_optional<std::string>(
"<xmlattr>.body2");
796 auto name =
v.second.get_optional<std::string>(
"<xmlattr>.name");
803 auto anchor =
v.second.get_optional<std::string>(
"<xmlattr>.anchor");
805 eq.
anchor = internal::getVectorFromStream<3>(*anchor);
814 if (
pt.get_child_optional(
"mujoco"))
815 el =
pt.get_child(
"mujoco");
817 throw std::invalid_argument(
"This is not a standard mujoco model. Cannot parse it.");
822 if (
v.first ==
"<xmlattr>")
824 auto n_s =
v.second.get_optional<std::string>(
"model");
828 throw std::invalid_argument(
"Model is missing a name. Cannot parse it");
831 if (
v.first ==
"compiler")
834 if (
v.first ==
"default")
837 if (
v.first ==
"asset")
840 if (
v.first ==
"keyframe")
843 if (
v.first ==
"worldbody")
845 boost::optional<std::string> childClass;
849 if (
v.first ==
"equality")
858 boost::property_tree::read_xml(xmlStr,
pt);
862 template<
typename TypeX,
typename TypeY,
typename TypeZ,
typename TypeUnaligned>
865 if (
axis.isApprox(Eigen::Vector3d::UnitX()))
867 else if (
axis.isApprox(Eigen::Vector3d::UnitY()))
869 else if (
axis.isApprox(Eigen::Vector3d::UnitZ()))
872 return TypeUnaligned(
axis.normalized());
888 UrdfVisitor::JointType jType;
895 jType = UrdfVisitor::FLOATING;
901 jType = UrdfVisitor::PRISMATIC;
907 jType = UrdfVisitor::SPHERICAL;
913 jType = UrdfVisitor::REVOLUTE;
916 throw std::invalid_argument(
"Unknown joint type");
919 jType, joint.
axis, parentFrameId, jointInParent, joint.
jointName, inert, bodyInJoint,
952 std::string jointName = nameOfBody +
"_fixed";
953 urdfVisitor << jointName <<
" being parsed." <<
'\n';
955 urdfVisitor.addFixedJointAndBody(parentFrameId, bodyPose, jointName, inert, nameOfBody);
959 bool composite =
false;
960 SE3 jointPlacement, firstJointPlacement, prevJointPlacement =
SE3::Identity();
964 std::string jointName;
971 jointName =
"Composite_" + firstOne.
jointName;
987 if (joint.jointType ==
"free")
988 throw std::invalid_argument(
"Joint Composite trying to be created with a freeFlyer");
990 SE3 jointInParent = bodyPose * joint.jointPlacement;
991 bodyInJoint = joint.jointPlacement.
inverse();
994 firstJointPlacement = jointInParent;
999 jointPlacement = prevJointPlacement.
inverse() * jointInParent;
1000 if (joint.jointType ==
"slide")
1003 createJoint<JointModelPX, JointModelPY, JointModelPZ, JointModelPrismaticUnaligned>(
1007 rangeCompo = rangeCompo.
concatenate<1, 1>(joint.range);
1009 else if (joint.jointType ==
"ball")
1012 rangeCompo = rangeCompo.
concatenate<4, 3>(joint.range.setDimension<4, 3>());
1014 else if (joint.jointType ==
"hinge")
1017 createJoint<JointModelRX, JointModelRY, JointModelRZ, JointModelRevoluteUnaligned>(
1020 rangeCompo = rangeCompo.
concatenate<1, 1>(joint.range);
1023 throw std::invalid_argument(
"Unknown joint type trying to be parsed.");
1025 prevJointPlacement = jointInParent;
1030 frame.parentJoint, jointM,
frame.placement * firstJointPlacement, jointName,
1034 urdfVisitor.appendBodyToJoint(jointFrameId, inert, bodyInJoint, nameOfBody);
1054 if (joint.jointType ==
"free")
1059 else if (joint.jointType ==
"ball")
1064 else if (joint.jointType ==
"slide" || joint.jointType ==
"hinge")
1076 if (keyframe.size() == model_nq)
1078 Eigen::VectorXd qpos(model_nq);
1079 for (std::size_t
i = 1;
i <
urdfVisitor.model.joints.size();
i++)
1082 int idx_q = joint.idx_q();
1083 int nq = joint.nq();
1085 Eigen::VectorXd qpos_j = keyframe.segment(
idx_q,
nq);
1087 if (joint.shortname() ==
"JointModelFreeFlyer")
1089 Eigen::Vector4d new_quat(qpos_j(4), qpos_j(5), qpos_j(6), qpos_j(3));
1090 qpos_j.tail(4) = new_quat;
1092 else if (joint.shortname() ==
"JointModelSpherical")
1094 Eigen::Vector4d new_quat(qpos_j(1), qpos_j(2), qpos_j(3), qpos_j(0));
1097 else if (joint.shortname() ==
"JointModelComposite")
1099 for (
const auto & joint_ : boost::get<JointModelComposite>(joint.toVariant()).joints)
1101 int idx_q_ = joint_.idx_q() -
idx_q;
1102 int nq_ = joint_.nq();
1103 if (joint_.shortname() ==
"JointModelSpherical")
1105 Eigen::Vector4d new_quat(
1106 qpos_j(idx_q_ + 1), qpos_j(idx_q_ + 2), qpos_j(idx_q_ + 3), qpos_j(idx_q_));
1107 qpos_j.segment(idx_q_, nq_) = new_quat;
1110 qpos_j.segment(idx_q_, nq_) -=
q_ref.segment(idx_q_, nq_);
1116 qpos.segment(
idx_q,
nq) = qpos_j;
1119 urdfVisitor.model.referenceConfigurations.insert(std::make_pair(keyName, qpos));
1122 throw std::invalid_argument(
"Keyframe size does not match model size");