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())
 
   63               std::invalid_argument, 
"Cannot find extension for one of the mesh/texture");
 
   65           auto st = filePath.stem();
 
   70               std::invalid_argument, 
"Cannot find a name for one of the mesh.texture");
 
   76         const std::string & dir,
 
   77         const std::string & modelPath,
 
   80         namespace fs = boost::filesystem;
 
   83         if (filePath.is_absolute() && !strippath)
 
   92           if (meshPath.is_absolute())
 
   97             return (mainPath.parent_path() / meshPath / 
filename);
 
  109         Eigen::Matrix3d aa1 =
 
  111         Eigen::Matrix3d aa2 =
 
  113         Eigen::Matrix3d aa3 =
 
  116         return aa1 * aa2 * aa3;
 
  119       template<
int Nq, 
int Nv>
 
  122         typedef UrdfVisitor::Vector Vector;
 
  123         const double infty = std::numeric_limits<double>::infinity();
 
  126         ret.
maxEffort = Vector::Constant(Nv, infty);
 
  127         ret.
maxVel = Vector::Constant(Nv, infty);
 
  128         ret.
maxConfig = Vector::Constant(Nq, 1.01);
 
  129         ret.
minConfig = Vector::Constant(Nq, -1.01);
 
  130         ret.
friction = Vector::Constant(Nv, 0.);
 
  131         ret.
damping = Vector::Constant(Nv, 0.);
 
  139       template<
int Nq, 
int Nv>
 
  176         if (!use_limits && el.get_optional<std::string>(
"<xmlattr>.range"))
 
  178             std::invalid_argument, 
"Range limit is specified but it was not specify to use it.");
 
  181         auto type_s = el.get_optional<std::string>(
"<xmlattr>.type");
 
  186         auto ax = el.get_optional<std::string>(
"<xmlattr>.axis");
 
  188           axis = internal::getVectorFromStream<3>(*
ax);
 
  191         auto range_ = el.get_optional<std::string>(
"<xmlattr>.range");
 
  194           Eigen::Vector2d rangeT = internal::getVectorFromStream<2>(*range_);
 
  199         range_ = el.get_optional<std::string>(
"<xmlattr>.actuatorfrcrange");
 
  202           Eigen::Vector2d rangeT = internal::getVectorFromStream<2>(*range_);
 
  207         auto value = el.get_optional<
double>(
"<xmlattr>.springref");
 
  212         value = el.get_optional<
double>(
"<xmlattr>.damping");
 
  216         value = el.get_optional<
double>(
"<xmlattr>.armature");
 
  221         value = el.get_optional<
double>(
"<xmlattr>.frictionloss");
 
  225         value = el.get_optional<
double>(
"<xmlattr>.ref");
 
  234               std::invalid_argument,
 
  235               "Reference position can only be used with hinge or slide joints.");
 
  242         bool use_limit = 
true;
 
  244         auto name_s = el.get_optional<std::string>(
"<xmlattr>.name");
 
  255           auto use_ls = el.get_optional<std::string>(
"<xmlattr>.limited");
 
  256           use_limit = *use_ls == 
"true";
 
  266           if (
auto joint_p = classD.
classElement.get_child_optional(
"joint"))
 
  273           if (
auto joint_p = classE.
classElement.get_child_optional(
"joint"))
 
  277         auto cl_s = el.get_optional<std::string>(
"<xmlattr>.class");
 
  280           std::string className = *cl_s;
 
  282           if (
auto joint_p = classE.
classElement.get_child_optional(
"joint"))
 
  295         auto pos = el.get_optional<std::string>(
"<xmlattr>.pos");
 
  297           placement.translation() = internal::getVectorFromStream<3>(*
pos);
 
  301         auto rot_s = el.get_optional<std::string>(
"<xmlattr>.quat");
 
  304           Eigen::Vector4d 
quat = internal::getVectorFromStream<4>(*rot_s);
 
  307           quaternion.normalize();
 
  308           placement.rotation() = quaternion.toRotationMatrix();
 
  311         else if ((rot_s = el.get_optional<std::string>(
"<xmlattr>.axisangle")))
 
  313           Eigen::Vector4d axis_angle = internal::getVectorFromStream<4>(*rot_s);
 
  315           double angle = axis_angle(3);
 
  318           placement.rotation() = angleAxis.toRotationMatrix();
 
  321         else if ((rot_s = el.get_optional<std::string>(
"<xmlattr>.euler")))
 
  323           Eigen::Vector3d angles = internal::getVectorFromStream<3>(*rot_s);
 
  327         else if ((rot_s = el.get_optional<std::string>(
"<xmlattr>.xyaxes")))
 
  329           Eigen::Matrix<double, 6, 1> xyaxes = internal::getVectorFromStream<6>(*rot_s);
 
  331           Eigen::Vector3d xAxis = xyaxes.head(3);
 
  333           Eigen::Vector3d yAxis = xyaxes.tail(3);
 
  336           double d = xAxis.dot(yAxis);
 
  340           Eigen::Vector3d zAxis = xAxis.cross(yAxis);
 
  350         else if ((rot_s = el.get_optional<std::string>(
"<xmlattr>.zaxis")))
 
  352           Eigen::Vector3d zaxis = internal::getVectorFromStream<3>(*rot_s);
 
  355             Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitZ(), zaxis).toRotationMatrix();
 
  366             std::invalid_argument, 
"Mass of body is not supposed to be negative");
 
  368         Inertia::Vector3 
com;
 
  369         auto com_s = el.get_optional<std::string>(
"<xmlattr>.pos");
 
  371           com = internal::getVectorFromStream<3>(*com_s);
 
  373           com = Inertia::Vector3::Zero();
 
  377         Inertia::Matrix3 I = Eigen::Matrix3d::Identity();
 
  379         auto inertia_s = el.get_optional<std::string>(
"<xmlattr>.diaginertia");
 
  382           Eigen::Vector3d inertiaDiag = internal::getVectorFromStream<3>(*inertia_s);
 
  383           I = inertiaDiag.asDiagonal();
 
  386         else if ((inertia_s = el.get_optional<std::string>(
"<xmlattr>.fullinertia")))
 
  390           inertiaStream >> I(0, 0);
 
  391           inertiaStream >> I(1, 1);
 
  392           inertiaStream >> I(2, 2);
 
  393           inertiaStream >> I(0, 1);
 
  394           inertiaStream >> I(0, 2);
 
  395           inertiaStream >> I(1, 2);
 
  403         for (
int i = 0; 
i < 3; 
i++)
 
  411         const boost::optional<std::string> & childClass,
 
  412         const std::string & parentName)
 
  415         auto chcl_s = childClass;
 
  419             std::invalid_argument, 
"Cannot get inertia from geom and no inertia was found");
 
  421         bool usegeominertia = 
false;
 
  423           usegeominertia = 
true;
 
  426           usegeominertia = 
true;
 
  431           if (
v.first == 
"<xmlattr>")
 
  434             auto name_s = 
v.second.get_optional<std::string>(
"name");
 
  438               currentBody.
bodyName = parentName + 
"Bis";
 
  445             if (
auto chcl_st = 
v.second.get_optional<std::string>(
"childclass"))
 
  454             auto cl_s = 
v.second.get_optional<std::string>(
"class");
 
  461           if (
v.first == 
"inertial" && !usegeominertia)
 
  465           if (
v.first == 
"geom")
 
  468             currentGeom.
fill(
v.second, currentBody, *
this);
 
  473           if (
v.first == 
"joint")
 
  476             currentJoint.
fill(
v.second, currentBody, *
this);
 
  479           if (
v.first == 
"freejoint")
 
  483             auto jointName = 
v.second.get_optional<std::string>(
"<xmlattr>.name");
 
  491           if (
v.first == 
"site")
 
  494             currentSite.
fill(
v.second, currentBody, *
this);
 
  497           if (
v.first == 
"body")
 
  505           Inertia inert_temp(Inertia::Zero());
 
  509               inert_temp += geom.geomPlacement.act(geom.geomInertia);
 
  518         namespace fs = boost::filesystem;
 
  520         auto file = el.get_optional<std::string>(
"<xmlattr>.file");
 
  521         auto name_ = el.get_optional<std::string>(
"<xmlattr>.name");
 
  522         auto type = el.get_optional<std::string>(
"<xmlattr>.type");
 
  531           std::cout << 
"Warning - Only texture with files are supported" << std::endl;
 
  544         auto str_v = el.get_optional<std::string>(
"<xmlattr>.type");
 
  548         if ((str_v = el.get_optional<std::string>(
"<xmlattr>.gridsize")))
 
  549           text.
gridsize = internal::getVectorFromStream<2>(*str_v);
 
  558         auto n = el.get_optional<std::string>(
"<xmlattr>.name");
 
  568           if (
auto mat_p = classD.
classElement.get_child_optional(
"material"))
 
  569             mat.goThroughElement(*mat_p);
 
  571         auto cl_s = el.get_optional<std::string>(
"<xmlattr>.class");
 
  574           std::string className = *cl_s;
 
  576           if (
auto mat_p = classE.
classElement.get_child_optional(
"material"))
 
  577             mat.goThroughElement(*mat_p);
 
  580         mat.goThroughElement(el);
 
  587         namespace fs = boost::filesystem;
 
  590         auto file = el.get_optional<std::string>(
"<xmlattr>.file");
 
  591         auto scale = el.get_optional<std::string>(
"<xmlattr>.scale");
 
  593           mesh.scale = internal::getVectorFromStream<3>(*scale);
 
  606         auto vertex = el.get_optional<std::string>(
"<xmlattr>.vertex");
 
  610             std::invalid_argument, 
"Only meshes with files/vertices are supported.")
 
  613         auto name = el.get_optional<std::string>(
"<xmlattr>.name");
 
  617             std::invalid_argument, 
"Mesh with vertices without a name is not supported");
 
  622         if (meshVertices.size() % 3 != 0)
 
  625             std::invalid_argument, 
"Number of vertices is not a multiple of 3");
 
  629         const auto numVertices = meshVertices.size() / 3;
 
  630         Eigen::MatrixX3d vertices(numVertices, 3);
 
  631         for (
auto i = 0; 
i < numVertices; ++
i)
 
  633           vertices.row(
i) = meshVertices.segment<3>(3 * 
i).transpose();
 
  635         mesh.vertices = vertices;
 
  643           if (
v.first == 
"mesh")
 
  646           if (
v.first == 
"material")
 
  649           if (
v.first == 
"texture")
 
  652           if (
v.first == 
"hfield")
 
  659         boost::optional<std::string> nameClass;
 
  663           if (
v.first == 
"<xmlattr>")
 
  665             nameClass = 
v.second.get_optional<std::string>(
"class");
 
  672               mapOfClasses.insert(std::make_pair(*nameClass, classDefault));
 
  676                 std::invalid_argument, 
"Class does not have a name. Cannot parse model.");
 
  678           else if (
v.first == 
"default")
 
  680           else if (parentTag == 
"mujoco" && 
v.first != 
"<xmlattr>")
 
  683             classDefault.
className = 
"mujoco_default";
 
  685             mapOfClasses.insert(std::make_pair(
"mujoco_default", classDefault));
 
  693         auto auto_s = el.get_optional<std::string>(
"<xmlattr>.autolimits");
 
  695           if (*auto_s == 
"true")
 
  699         auto strip_s = el.get_optional<std::string>(
"<xmlattr>.strippath");
 
  701           if (*strip_s == 
"true")
 
  705         auto dir = el.get_optional<std::string>(
"<xmlattr>.assetdir");
 
  712         if ((dir = el.get_optional<std::string>(
"<xmlattr>.meshdir")))
 
  715         if ((dir = el.get_optional<std::string>(
"<xmlattr>.texturedir")))
 
  718         auto value_v = el.get_optional<
double>(
"<xmlattr>.boundmass");
 
  722         if ((value_v = el.get_optional<
double>(
"<xmlattr>.boundinertia")))
 
  725         auto in_g = el.get_optional<std::string>(
"<xmlattr>.inertiafromgeom");
 
  730           else if (*in_g == 
"false")
 
  735         auto angle_s = el.get_optional<std::string>(
"<xmlattr>.angle");
 
  737           if (*angle_s == 
"radian")
 
  740         auto eulerS = el.get_optional<std::string>(
"<xmlattr>.eulerseq");
 
  743           std::string eulerseq = *eulerS;
 
  744           if (eulerseq.find_first_not_of(
"xyzXYZ") != std::string::npos || eulerseq.size() != 3)
 
  747               std::invalid_argument, 
"Model tried to use euler angles but euler sequence is wrong");
 
  752             for (std::size_t 
i = 0; 
i < eulerseq.size(); 
i++)
 
  788           if (
v.first == 
"key")
 
  790             auto nameKey = 
v.second.get_optional<std::string>(
"<xmlattr>.name");
 
  793               auto configVectorS = 
v.second.get_optional<std::string>(
"<xmlattr>.qpos");
 
  796                 Eigen::VectorXd configVector =
 
  798                 mapOfConfigs.insert(std::make_pair(*nameKey, configVector));
 
  809           std::string 
type = 
v.first;
 
  815           if (
type != 
"connect")
 
  825           auto body1 = 
v.second.get_optional<std::string>(
"<xmlattr>.body1");
 
  832           auto body2 = 
v.second.get_optional<std::string>(
"<xmlattr>.body2");
 
  837           auto name = 
v.second.get_optional<std::string>(
"<xmlattr>.name");
 
  844           auto anchor = 
v.second.get_optional<std::string>(
"<xmlattr>.anchor");
 
  846             eq.
anchor = internal::getVectorFromStream<3>(*anchor);
 
  855         if (
pt.get_child_optional(
"mujoco"))
 
  856           el = 
pt.get_child(
"mujoco");
 
  859             std::invalid_argument, 
"This is not a standard mujoco model. Cannot parse it.");
 
  864           if (
v.first == 
"<xmlattr>")
 
  866             auto n_s = 
v.second.get_optional<std::string>(
"model");
 
  871                 std::invalid_argument, 
"Model is missing a name. Cannot parse it");
 
  874           if (
v.first == 
"compiler")
 
  877           if (
v.first == 
"default")
 
  880           if (
v.first == 
"asset")
 
  883           if (
v.first == 
"keyframe")
 
  886           if (
v.first == 
"worldbody")
 
  888             boost::optional<std::string> childClass;
 
  892           if (
v.first == 
"equality")
 
  901         boost::property_tree::read_xml(xmlStr, 
pt);
 
  905       template<
typename TypeX, 
typename TypeY, 
typename TypeZ, 
typename TypeUnaligned>
 
  908         if (
axis.isApprox(Eigen::Vector3d::UnitX()))
 
  910         else if (
axis.isApprox(Eigen::Vector3d::UnitY()))
 
  912         else if (
axis.isApprox(Eigen::Vector3d::UnitZ()))
 
  915           return TypeUnaligned(
axis.normalized());
 
  931         UrdfVisitor::JointType jType;
 
  938           jType = UrdfVisitor::FLOATING;
 
  944           jType = UrdfVisitor::PRISMATIC;
 
  950           jType = UrdfVisitor::SPHERICAL;
 
  956           jType = UrdfVisitor::REVOLUTE;
 
  962           jType, joint.
axis, parentFrameId, jointInParent, joint.
jointName, inert, bodyInJoint,
 
  995           std::string jointName = nameOfBody + 
"_fixed";
 
  996           urdfVisitor << jointName << 
" being parsed." << 
'\n';
 
  998           urdfVisitor.addFixedJointAndBody(parentFrameId, bodyPose, jointName, inert, nameOfBody);
 
 1002         bool composite = 
false;
 
 1003         SE3 jointPlacement, firstJointPlacement, prevJointPlacement = SE3::Identity();
 
 1007         std::string jointName;
 
 1014           jointName = 
"Composite_" + firstOne.
jointName;
 
 1019         bool isFirst = 
true;
 
 1030             if (joint.jointType == 
"free")
 
 1032                 std::invalid_argument, 
"Joint Composite trying to be created with a freeFlyer");
 
 1034             SE3 jointInParent = bodyPose * joint.jointPlacement;
 
 1035             bodyInJoint = joint.jointPlacement.inverse();
 
 1038               firstJointPlacement = jointInParent;
 
 1039               jointPlacement = SE3::Identity();
 
 1043               jointPlacement = prevJointPlacement.inverse() * jointInParent;
 
 1044             if (joint.jointType == 
"slide")
 
 1047                 createJoint<JointModelPX, JointModelPY, JointModelPZ, JointModelPrismaticUnaligned>(
 
 1051               rangeCompo = rangeCompo.
concatenate<1, 1>(joint.range);
 
 1053             else if (joint.jointType == 
"ball")
 
 1056               rangeCompo = rangeCompo.
concatenate<4, 3>(joint.range.setDimension<4, 3>());
 
 1058             else if (joint.jointType == 
"hinge")
 
 1061                 createJoint<JointModelRX, JointModelRY, JointModelRZ, JointModelRevoluteUnaligned>(
 
 1064               rangeCompo = rangeCompo.
concatenate<1, 1>(joint.range);
 
 1068                 std::invalid_argument, 
"Unknown joint type trying to be parsed.");
 
 1070             prevJointPlacement = jointInParent;
 
 1075             frame.parentJoint, jointM, 
frame.placement * firstJointPlacement, jointName,
 
 1079           urdfVisitor.appendBodyToJoint(jointFrameId, inert, bodyInJoint, nameOfBody);
 
 1100           if (joint.jointType == 
"free")
 
 1105           else if (joint.jointType == 
"ball")
 
 1110           else if (joint.jointType == 
"slide" || joint.jointType == 
"hinge")
 
 1122         if (keyframe.size() == model_nq)
 
 1124           Eigen::VectorXd qpos(model_nq);
 
 1125           for (std::size_t 
i = 1; 
i < 
urdfVisitor.model.joints.size(); 
i++)
 
 1128             int idx_q = joint.idx_q();
 
 1129             int nq = joint.nq();
 
 1131             Eigen::VectorXd qpos_j = keyframe.segment(
idx_q, 
nq);
 
 1133             if (joint.shortname() == 
"JointModelFreeFlyer")
 
 1135               Eigen::Vector4d new_quat(qpos_j(4), qpos_j(5), qpos_j(6), qpos_j(3));
 
 1136               qpos_j.tail(4) = new_quat;
 
 1138             else if (joint.shortname() == 
"JointModelSpherical")
 
 1140               Eigen::Vector4d new_quat(qpos_j(1), qpos_j(2), qpos_j(3), qpos_j(0));
 
 1143             else if (joint.shortname() == 
"JointModelComposite")
 
 1145               for (
const auto & joint_ : boost::get<JointModelComposite>(joint.toVariant()).joints)
 
 1147                 int idx_q_ = joint_.idx_q() - 
idx_q;
 
 1148                 int nq_ = joint_.nq();
 
 1149                 if (joint_.shortname() == 
"JointModelSpherical")
 
 1151                   Eigen::Vector4d new_quat(
 
 1152                     qpos_j(idx_q_ + 1), qpos_j(idx_q_ + 2), qpos_j(idx_q_ + 3), qpos_j(idx_q_));
 
 1153                   qpos_j.segment(idx_q_, nq_) = new_quat;
 
 1156                   qpos_j.segment(idx_q_, nq_) -= 
q_ref.segment(idx_q_, nq_);
 
 1162             qpos.segment(
idx_q, 
nq) = qpos_j;
 
 1165           urdfVisitor.model.referenceConfigurations.insert(std::make_pair(keyName, qpos));
 
 1180           jointPlacement.setIdentity();
 
 1181           jointPlacement.translation() = eq.
anchor;