mjcf-graph.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2016-2024 CNRS INRIA
3 //
4 
8 
9 namespace pinocchio
10 {
11  namespace mjcf
12  {
13  namespace details
14  {
16  typedef pinocchio::urdf::details::
17  UrdfVisitor<double, 0, ::pinocchio::JointCollectionDefaultTpl>
19 
20  // supported elements from mjcf
21  static const std::array<std::string, 3> ELEMENTS = {"joint", "geom", "site"};
22 
26  static void copyPtree(const ptree & src, ptree & dst)
27  {
28  for (const ptree::value_type & v : src)
29  dst.put(ptree::path_type(v.first), v.second.data());
30  }
31 
35  static void updateClassElement(ptree & current, const ptree & parent)
36  {
37  for (const std::string & el : ELEMENTS)
38  {
39  std::string path = el + ".<xmlattr>";
40  if (parent.get_child_optional(path))
41  {
42  const ptree default_value = ptree();
43  ptree attr_parent = parent.get_child(path, default_value);
44  const ptree & attr_current = current.get_child(path, default_value);
45  // To only copy non existing attribute in current, we copy all current
46  // attribute (replacing) into a parent copy then we replace current with the new
47  // ptree
48  copyPtree(attr_current, attr_parent);
49  current.put_child(path, attr_parent);
50  }
51  }
52  }
53 
54  static std::string getName(const ptree & el, const boost::filesystem::path & filePath)
55  {
56  auto n = el.get_optional<std::string>("<xmlattr>.name");
57  if (n)
58  return *n;
59  else
60  {
61  if (filePath.extension().empty())
62  throw std::invalid_argument("Cannot find extension for one of the mesh/texture");
63 
64  auto st = filePath.stem();
65  if (!st.empty())
66  return st.string();
67  else
68  throw std::invalid_argument("Cannot find a name for one of the mesh.texture");
69  }
70  }
71 
73  bool strippath,
74  const std::string & dir,
75  const std::string & modelPath,
76  const boost::filesystem::path & filePath)
77  {
78  namespace fs = boost::filesystem;
79 
80  // Check if filename still has Absolute path, like said in mujoco doc
81  if (filePath.is_absolute() && !strippath)
82  return filePath;
83  else
84  {
85  auto filename = filePath;
86  if (strippath)
87  filename = filePath.filename();
88 
89  fs::path meshPath(dir);
90  if (meshPath.is_absolute())
91  return (meshPath / filename);
92  else
93  {
94  fs::path mainPath(modelPath);
95  return (mainPath.parent_path() / meshPath / filename);
96  }
97  }
98  }
99 
100  double MjcfCompiler::convertAngle(const double & angle_) const
101  {
102  return angle_ * angle_converter;
103  }
104 
105  Eigen::Matrix3d MjcfCompiler::convertEuler(const Eigen::Vector3d & angles) const
106  {
107  Eigen::Matrix3d aa1 =
108  Eigen::AngleAxisd(convertAngle(angles(0)), mapEulerAngles.col(0)).toRotationMatrix();
109  Eigen::Matrix3d aa2 =
110  Eigen::AngleAxisd(convertAngle(angles(1)), mapEulerAngles.col(1)).toRotationMatrix();
111  Eigen::Matrix3d aa3 =
112  Eigen::AngleAxisd(convertAngle(angles(2)), mapEulerAngles.col(2)).toRotationMatrix();
113 
114  return aa1 * aa2 * aa3;
115  }
116 
117  template<int Nq, int Nv>
119  {
120  typedef UrdfVisitor::Vector Vector;
121  const double infty = std::numeric_limits<double>::infinity();
122 
123  RangeJoint ret;
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.);
130  ret.armature = Vector::Constant(Nv, armature[0]);
134  return ret;
135  }
136 
137  template<int Nq, int Nv>
139  {
140  assert(range.maxEffort.size() == Nv);
141  assert(range.minConfig.size() == Nq);
142 
143  RangeJoint ret(*this);
144  ret.maxEffort.conservativeResize(maxEffort.size() + Nv);
145  ret.maxEffort.tail(Nv) = range.maxEffort;
146  ret.maxVel.conservativeResize(maxVel.size() + Nv);
147  ret.maxVel.tail(Nv) = range.maxVel;
148 
149  ret.minConfig.conservativeResize(minConfig.size() + Nq);
150  ret.minConfig.tail(Nq) = range.minConfig;
151  ret.maxConfig.conservativeResize(maxConfig.size() + Nq);
152  ret.maxConfig.tail(Nq) = range.maxConfig;
153 
154  ret.damping.conservativeResize(damping.size() + Nv);
155  ret.damping.tail(Nv) = range.damping;
156  ret.friction.conservativeResize(friction.size() + Nv);
157  ret.friction.tail(Nv) = range.friction;
158 
159  ret.springReference.conservativeResize(springReference.size() + 1);
160  ret.springReference.tail(1) = range.springReference;
161  ret.springStiffness.conservativeResize(springStiffness.size() + 1);
162  ret.springStiffness.tail(1) = range.springStiffness;
163 
164  ret.armature.conservativeResize(armature.size() + Nv);
165  ret.armature.tail(Nv) = range.armature;
166 
167  return ret;
168  }
169 
171  const ptree & el, bool use_limits, const MjcfCompiler & currentCompiler)
172  {
173 
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.");
176 
177  // Type
178  auto type_s = el.get_optional<std::string>("<xmlattr>.type");
179  if (type_s)
180  jointType = *type_s;
181 
182  // Axis
183  auto ax = el.get_optional<std::string>("<xmlattr>.axis");
184  if (ax)
185  axis = internal::getVectorFromStream<3>(*ax);
186 
187  // Range
188  auto range_ = el.get_optional<std::string>("<xmlattr>.range");
189  if (range_)
190  {
191  Eigen::Vector2d rangeT = internal::getVectorFromStream<2>(*range_);
192  range.minConfig[0] = currentCompiler.convertAngle(rangeT(0));
193  range.maxConfig[0] = currentCompiler.convertAngle(rangeT(1));
194  }
195  // Effort limit
196  range_ = el.get_optional<std::string>("<xmlattr>.actuatorfrcrange");
197  if (range_)
198  {
199  Eigen::Vector2d rangeT = internal::getVectorFromStream<2>(*range_);
200  range.maxEffort[0] = rangeT(1);
201  }
202 
203  // Spring
204  auto value = el.get_optional<double>("<xmlattr>.springref");
205  if (value)
207 
208  // damping
209  value = el.get_optional<double>("<xmlattr>.damping");
210  if (value)
211  range.damping[0] = *value;
212 
213  value = el.get_optional<double>("<xmlattr>.armature");
214  if (value)
215  range.armature[0] = *value;
216 
217  // friction loss
218  value = el.get_optional<double>("<xmlattr>.frictionloss");
219  if (value)
221 
222  value = el.get_optional<double>("<xmlattr>.ref");
223  if (value)
224  {
225  if (jointType == "slide")
226  posRef = *value;
227  else if (jointType == "hinge")
228  posRef = currentCompiler.convertAngle(*value);
229  else
230  throw std::invalid_argument(
231  "Reference position can only be used with hinge or slide joints.");
232  }
233  }
234 
236  const ptree & el, const MjcfBody & currentBody, const MjcfGraph & currentGraph)
237  {
238  bool use_limit = true;
239  // Name
240  auto name_s = el.get_optional<std::string>("<xmlattr>.name");
241  if (name_s)
242  jointName = *name_s;
243  else
244  jointName =
245  currentBody.bodyName + "Joint_" + std::to_string(currentBody.jointChildren.size());
246 
247  // Check if we need to check for limited argument
248  if (!currentGraph.compilerInfo.autolimits)
249  {
250  use_limit = false;
251  auto use_ls = el.get_optional<std::string>("<xmlattr>.limited");
252  use_limit = *use_ls == "true";
253  }
254 
255  // Placement
256  jointPlacement = currentGraph.convertPosition(el);
257 
258  // default < ChildClass < Class < Real Joint
259  if (currentGraph.mapOfClasses.find("mujoco_default") != currentGraph.mapOfClasses.end())
260  {
261  const MjcfClass & classD = currentGraph.mapOfClasses.at("mujoco_default");
262  if (auto joint_p = classD.classElement.get_child_optional("joint"))
263  goThroughElement(*joint_p, use_limit, currentGraph.compilerInfo);
264  }
265  // childClass
266  if (currentBody.childClass != "")
267  {
268  const MjcfClass & classE = currentGraph.mapOfClasses.at(currentBody.childClass);
269  if (auto joint_p = classE.classElement.get_child_optional("joint"))
270  goThroughElement(*joint_p, use_limit, currentGraph.compilerInfo);
271  }
272  // Class
273  auto cl_s = el.get_optional<std::string>("<xmlattr>.class");
274  if (cl_s)
275  {
276  std::string className = *cl_s;
277  const MjcfClass & classE = currentGraph.mapOfClasses.at(className);
278  if (auto joint_p = classE.classElement.get_child_optional("joint"))
279  goThroughElement(*joint_p, use_limit, currentGraph.compilerInfo);
280  }
281  // Joint
282  goThroughElement(el, use_limit, currentGraph.compilerInfo);
283  }
284 
286  {
287  SE3 placement;
288  placement.setIdentity();
289 
290  // position
291  auto pos = el.get_optional<std::string>("<xmlattr>.pos");
292  if (pos)
293  placement.translation() = internal::getVectorFromStream<3>(*pos);
294 
296  // Quaternion (w, x, y, z)
297  auto rot_s = el.get_optional<std::string>("<xmlattr>.quat");
298  if (rot_s)
299  {
300  Eigen::Vector4d quat = internal::getVectorFromStream<4>(*rot_s);
301 
302  Eigen::Quaterniond quaternion(quat(0), quat(1), quat(2), quat(3));
303  quaternion.normalize();
304  placement.rotation() = quaternion.toRotationMatrix();
305  }
306  // Axis Angle
307  else if ((rot_s = el.get_optional<std::string>("<xmlattr>.axisangle")))
308  {
309  Eigen::Vector4d axis_angle = internal::getVectorFromStream<4>(*rot_s);
310 
311  double angle = axis_angle(3);
312 
313  Eigen::AngleAxisd angleAxis(compilerInfo.convertAngle(angle), axis_angle.head(3));
314  placement.rotation() = angleAxis.toRotationMatrix();
315  }
316  // Euler Angles
317  else if ((rot_s = el.get_optional<std::string>("<xmlattr>.euler")))
318  {
319  Eigen::Vector3d angles = internal::getVectorFromStream<3>(*rot_s);
320 
321  placement.rotation() = compilerInfo.convertEuler(angles);
322  }
323  else if ((rot_s = el.get_optional<std::string>("<xmlattr>.xyaxes")))
324  {
325  Eigen::Matrix<double, 6, 1> xyaxes = internal::getVectorFromStream<6>(*rot_s);
326 
327  Eigen::Vector3d xAxis = xyaxes.head(3);
328  xAxis.normalize();
329  Eigen::Vector3d yAxis = xyaxes.tail(3);
330 
331  // make y axis orthogonal to x axis, normalize
332  double d = xAxis.dot(yAxis);
333  yAxis -= xAxis * d;
334  yAxis.normalize();
335 
336  Eigen::Vector3d zAxis = xAxis.cross(yAxis);
337  zAxis.normalize();
338 
339  Eigen::Matrix3d rotation;
340  rotation.col(0) = xAxis;
341  rotation.col(1) = yAxis;
342  rotation.col(2) = zAxis;
343 
344  placement.rotation() = rotation;
345  }
346  else if ((rot_s = el.get_optional<std::string>("<xmlattr>.zaxis")))
347  {
348  Eigen::Vector3d zaxis = internal::getVectorFromStream<3>(*rot_s);
349  // Compute the rotation matrix that maps z_axis to unit z
350  placement.rotation() =
351  Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitZ(), zaxis).toRotationMatrix();
352  }
353  return placement;
354  }
355 
357  {
358  double mass = std::max(el.get<double>("<xmlattr>.mass"), compilerInfo.boundMass);
359  ;
360  if (mass < 0)
361  throw std::invalid_argument("Mass of body is not supposed to be negative");
362 
364  auto com_s = el.get_optional<std::string>("<xmlattr>.pos");
365  if (com_s)
366  com = internal::getVectorFromStream<3>(*com_s);
367  else
368  com = Inertia::Vector3::Zero();
369 
370  const Inertia::Matrix3 R = convertPosition(el).rotation();
371 
372  Inertia::Matrix3 I = Eigen::Matrix3d::Identity();
373 
374  auto inertia_s = el.get_optional<std::string>("<xmlattr>.diaginertia");
375  if (inertia_s)
376  {
377  Eigen::Vector3d inertiaDiag = internal::getVectorFromStream<3>(*inertia_s);
378  I = inertiaDiag.asDiagonal();
379  }
380 
381  else if ((inertia_s = el.get_optional<std::string>("<xmlattr>.fullinertia")))
382  {
383  // M(1,1), M(2,2), M(3,3), M(1,2), M(1,3), M(2,3)
384  std::istringstream inertiaStream = internal::getConfiguredStringStream(*inertia_s);
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);
391 
392  I(1, 0) = I(0, 1);
393  I(2, 0) = I(0, 2);
394  I(2, 1) = I(1, 2);
395  }
396 
397  // Extract the diagonal elements as a vector
398  for (int i = 0; i < 3; i++)
399  I(i, i) = std::max(I(i, i), compilerInfo.boundInertia);
400 
401  return Inertia(mass, com, R * I * R.transpose());
402  }
403 
405  const ptree & el,
406  const boost::optional<std::string> & childClass,
407  const std::string & parentName)
408  {
409  MjcfBody currentBody;
410  auto chcl_s = childClass;
411  // if inertiafromgeom is false and inertia does not exist - throw
412  if (!compilerInfo.inertiafromgeom && !el.get_child_optional("inertial"))
413  throw std::invalid_argument("Cannot get inertia from geom and no inertia was found");
414 
415  bool usegeominertia = false;
417  usegeominertia = true;
418  else if (
419  boost::indeterminate(compilerInfo.inertiafromgeom) && !el.get_child_optional("inertial"))
420  usegeominertia = true;
421 
422  for (const ptree::value_type & v : el)
423  {
424  // Current body node
425  if (v.first == "<xmlattr>")
426  {
427  // Name
428  auto name_s = v.second.get_optional<std::string>("name");
429  if (name_s)
430  currentBody.bodyName = *name_s;
431  else
432  currentBody.bodyName = parentName + "Bis";
433 
434  currentBody.bodyParent = parentName;
435  currentBody.bodyPlacement = convertPosition(el);
436 
437  bodiesList.push_back(currentBody.bodyName);
438 
439  if (auto chcl_st = v.second.get_optional<std::string>("childclass"))
440  {
441  chcl_s = chcl_st;
442  currentBody.childClass = *chcl_s;
443  }
444  else if (childClass)
445  currentBody.childClass = *chcl_s;
446 
447  // Class
448  auto cl_s = v.second.get_optional<std::string>("class");
449  if (cl_s)
450  currentBody.bodyClassName = *cl_s;
451 
452  // Still need to deal with gravcomp and figure out if we need mocap, and user param...
453  }
454  // Inertia
455  if (v.first == "inertial" && !usegeominertia)
456  currentBody.bodyInertia = convertInertiaFromMjcf(v.second);
457 
458  // Geom
459  if (v.first == "geom")
460  {
461  MjcfGeom currentGeom;
462  currentGeom.fill(v.second, currentBody, *this);
463  currentBody.geomChildren.push_back(currentGeom);
464  }
465 
466  // Joint
467  if (v.first == "joint")
468  {
469  MjcfJoint currentJoint;
470  currentJoint.fill(v.second, currentBody, *this);
471  currentBody.jointChildren.push_back(currentJoint);
472  }
473  if (v.first == "freejoint")
474  {
475  MjcfJoint currentJoint;
476  currentJoint.jointType = "free";
477  auto jointName = v.second.get_optional<std::string>("<xmlattr>.name");
478  if (jointName)
479  currentJoint.jointName = *jointName;
480  else
481  currentJoint.jointName = currentBody.bodyName + "_free";
482 
483  currentBody.jointChildren.push_back(currentJoint);
484  }
485  if (v.first == "site")
486  {
487  MjcfSite currentSite;
488  currentSite.fill(v.second, currentBody, *this);
489  currentBody.siteChildren.push_back(currentSite);
490  }
491  if (v.first == "body")
492  {
493  parseJointAndBody(v.second, chcl_s, currentBody.bodyName);
494  }
495  }
496  // Add all geom inertias if needed
497  if (usegeominertia)
498  {
499  Inertia inert_temp(Inertia::Zero());
500  for (const auto & geom : currentBody.geomChildren)
501  {
502  if (geom.geomKind != MjcfGeom::VISUAL)
503  inert_temp += geom.geomPlacement.act(geom.geomInertia);
504  }
505  currentBody.bodyInertia = inert_temp;
506  }
507  mapOfBodies.insert(std::make_pair(currentBody.bodyName, currentBody));
508  }
509 
511  {
512  namespace fs = boost::filesystem;
513  MjcfTexture text;
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");
517 
518  std::string name;
519  if (name_)
520  name = *name_;
521  else if (type && *type == "skybox")
522  name = *type;
523  if (!file)
524  {
525  std::cout << "Warning - Only texture with files are supported" << std::endl;
526  if (name.empty())
527  throw std::invalid_argument("Textures need a name.");
528  }
529  else
530  {
531  fs::path filePath(*file);
532  name = getName(el, filePath);
533 
534  text.filePath =
536  .string();
537  }
538  auto str_v = el.get_optional<std::string>("<xmlattr>.type");
539  if (str_v)
540  text.textType = *str_v;
541 
542  if ((str_v = el.get_optional<std::string>("<xmlattr>.gridsize")))
543  text.gridsize = internal::getVectorFromStream<2>(*str_v);
544 
545  mapOfTextures.insert(std::make_pair(name, text));
546  }
547 
549  {
550  std::string name;
552  auto n = el.get_optional<std::string>("<xmlattr>.name");
553  if (n)
554  name = *n;
555  else
556  throw std::invalid_argument("Material was given without a name");
557 
558  // default < Class < Attributes
559  if (mapOfClasses.find("mujoco_default") != mapOfClasses.end())
560  {
561  const MjcfClass & classD = mapOfClasses.at("mujoco_default");
562  if (auto mat_p = classD.classElement.get_child_optional("material"))
563  mat.goThroughElement(*mat_p);
564  }
565  auto cl_s = el.get_optional<std::string>("<xmlattr>.class");
566  if (cl_s)
567  {
568  std::string className = *cl_s;
569  const MjcfClass & classE = mapOfClasses.at(className);
570  if (auto mat_p = classE.classElement.get_child_optional("material"))
571  mat.goThroughElement(*mat_p);
572  }
573 
574  mat.goThroughElement(el);
575 
576  mapOfMaterials.insert(std::make_pair(name, mat));
577  }
578 
579  void MjcfGraph::parseMesh(const ptree & el)
580  {
581  namespace fs = boost::filesystem;
582 
583  MjcfMesh mesh;
584  auto file = el.get_optional<std::string>("<xmlattr>.file");
585  if (!file)
586  throw std::invalid_argument("Only meshes with files are supported");
587 
588  fs::path filePath(*file);
589  std::string name = getName(el, filePath);
590 
591  mesh.filePath =
593 
594  auto scale = el.get_optional<std::string>("<xmlattr>.scale");
595  if (scale)
596  mesh.scale = internal::getVectorFromStream<3>(*scale);
597 
598  mapOfMeshes.insert(std::make_pair(name, mesh));
599  }
600 
601  void MjcfGraph::parseAsset(const ptree & el)
602  {
603  for (const ptree::value_type & v : el)
604  {
605  if (v.first == "mesh")
606  parseMesh(v.second);
607 
608  if (v.first == "material")
609  parseMaterial(v.second);
610 
611  if (v.first == "texture")
612  parseTexture(v.second);
613 
614  if (v.first == "hfield")
615  throw std::invalid_argument("hfields are not supported yet");
616  }
617  }
618 
619  void MjcfGraph::parseDefault(ptree & el, const ptree & parent, const std::string & parentTag)
620  {
621  boost::optional<std::string> nameClass;
622  // Classes
623  for (ptree::value_type & v : el)
624  {
625  if (v.first == "<xmlattr>")
626  {
627  nameClass = v.second.get_optional<std::string>("class");
628  if (nameClass)
629  {
630  MjcfClass classDefault;
631  classDefault.className = *nameClass;
633  classDefault.classElement = el;
634  mapOfClasses.insert(std::make_pair(*nameClass, classDefault));
635  }
636  else
637  throw std::invalid_argument("Class does not have a name. Cannot parse model.");
638  }
639  else if (v.first == "default")
640  parseDefault(v.second, el, v.first);
641  else if (parentTag == "mujoco" && v.first != "<xmlattr>")
642  {
643  MjcfClass classDefault;
644  classDefault.className = "mujoco_default";
645  classDefault.classElement = el;
646  mapOfClasses.insert(std::make_pair("mujoco_default", classDefault));
647  }
648  }
649  }
650 
652  {
653  // get autolimits
654  auto auto_s = el.get_optional<std::string>("<xmlattr>.autolimits");
655  if (auto_s)
656  if (*auto_s == "true")
657  compilerInfo.autolimits = true;
658 
659  // strip path
660  auto strip_s = el.get_optional<std::string>("<xmlattr>.strippath");
661  if (strip_s)
662  if (*strip_s == "true")
663  compilerInfo.strippath = true;
664 
665  // get dir to mesh and texture
666  auto dir = el.get_optional<std::string>("<xmlattr>.assetdir");
667  if (dir)
668  {
669  compilerInfo.meshdir = *dir;
670  compilerInfo.texturedir = *dir;
671  }
672 
673  if ((dir = el.get_optional<std::string>("<xmlattr>.meshdir")))
674  compilerInfo.meshdir = *dir;
675 
676  if ((dir = el.get_optional<std::string>("<xmlattr>.texturedir")))
677  compilerInfo.texturedir = *dir;
678 
679  auto value_v = el.get_optional<double>("<xmlattr>.boundmass");
680  if (value_v)
681  compilerInfo.boundMass = *value_v;
682 
683  if ((value_v = el.get_optional<double>("<xmlattr>.boundinertia")))
684  compilerInfo.boundInertia = *value_v;
685 
686  auto in_g = el.get_optional<std::string>("<xmlattr>.inertiafromgeom");
687  if (in_g)
688  {
689  if (*in_g == "true")
691  else if (*in_g == "false")
693  }
694 
695  // angle radian or degree
696  auto angle_s = el.get_optional<std::string>("<xmlattr>.angle");
697  if (angle_s)
698  if (*angle_s == "radian")
700 
701  auto eulerS = el.get_optional<std::string>("<xmlattr>.eulerseq");
702  if (eulerS)
703  {
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");
708  else
709  {
710  // get index combination
711  for (std::size_t i = 0; i < eulerseq.size(); i++)
712  {
713  auto ci = static_cast<Eigen::Index>(i);
714  switch (eulerseq[i])
715  {
716  case 'x':
717  compilerInfo.mapEulerAngles.col(ci) = Eigen::Vector3d::UnitX();
718  break;
719  case 'X':
720  compilerInfo.mapEulerAngles.col(ci) = Eigen::Vector3d::UnitX();
721  break;
722  case 'y':
723  compilerInfo.mapEulerAngles.col(ci) = Eigen::Vector3d::UnitY();
724  break;
725  case 'Y':
726  compilerInfo.mapEulerAngles.col(ci) = Eigen::Vector3d::UnitY();
727  break;
728  case 'z':
729  compilerInfo.mapEulerAngles.col(ci) = Eigen::Vector3d::UnitZ();
730  break;
731  case 'Z':
732  compilerInfo.mapEulerAngles.col(ci) = Eigen::Vector3d::UnitZ();
733  break;
734  default:
735  throw std::invalid_argument("Euler Axis does not exist");
736  break;
737  }
738  }
739  }
740  }
741  }
742 
744  {
745  for (const ptree::value_type & v : el)
746  {
747  if (v.first == "key")
748  {
749  auto nameKey = v.second.get_optional<std::string>("<xmlattr>.name");
750  if (nameKey)
751  {
752  auto configVectorS = v.second.get_optional<std::string>("<xmlattr>.qpos");
753  if (configVectorS)
754  {
755  Eigen::VectorXd configVector =
757  mapOfConfigs.insert(std::make_pair(*nameKey, configVector));
758  }
759  }
760  }
761  }
762  }
763 
765  {
766  for (const ptree::value_type & v : el)
767  {
768  std::string type = v.first;
769  // List of supported constraints from mjcf description
770  // equality -> connect
771 
772  // The constraints below are not supported and will be ignored with the following
773  // warning: joint, flex, distance, weld
774  if (type != "connect")
775  {
776  // TODO(jcarpent): support extra constraint types such as joint, flex, distance, weld.
777  continue;
778  }
779 
780  MjcfEquality eq;
781  eq.type = type;
782 
783  // get the name of first body
784  auto body1 = v.second.get_optional<std::string>("<xmlattr>.body1");
785  if (body1)
786  eq.body1 = *body1;
787  else
788  throw std::invalid_argument("Equality constraint needs a first body");
789 
790  // get the name of second body
791  auto body2 = v.second.get_optional<std::string>("<xmlattr>.body2");
792  if (body2)
793  eq.body2 = *body2;
794 
795  // get the name of the constraint (if it exists)
796  auto name = v.second.get_optional<std::string>("<xmlattr>.name");
797  if (name)
798  eq.name = *name;
799  else
800  eq.name = eq.body1 + "_" + eq.body2 + "_constraint";
801 
802  // get the anchor position
803  auto anchor = v.second.get_optional<std::string>("<xmlattr>.anchor");
804  if (anchor)
805  eq.anchor = internal::getVectorFromStream<3>(*anchor);
806 
807  mapOfEqualities.insert(std::make_pair(eq.name, eq));
808  }
809  }
810 
812  {
814  if (pt.get_child_optional("mujoco"))
815  el = pt.get_child("mujoco");
816  else
817  throw std::invalid_argument("This is not a standard mujoco model. Cannot parse it.");
818 
819  for (const ptree::value_type & v : el)
820  {
821  // get model name
822  if (v.first == "<xmlattr>")
823  {
824  auto n_s = v.second.get_optional<std::string>("model");
825  if (n_s)
826  modelName = *n_s;
827  else
828  throw std::invalid_argument("Model is missing a name. Cannot parse it");
829  }
830 
831  if (v.first == "compiler")
832  parseCompiler(el.get_child("compiler"));
833 
834  if (v.first == "default")
835  parseDefault(el.get_child("default"), el, "mujoco");
836 
837  if (v.first == "asset")
838  parseAsset(el.get_child("asset"));
839 
840  if (v.first == "keyframe")
841  parseKeyFrame(el.get_child("keyframe"));
842 
843  if (v.first == "worldbody")
844  {
845  boost::optional<std::string> childClass;
846  parseJointAndBody(el.get_child("worldbody").get_child("body"), childClass);
847  }
848 
849  if (v.first == "equality")
850  {
851  parseEquality(el.get_child("equality"));
852  }
853  }
854  }
855 
856  void MjcfGraph::parseGraphFromXML(const std::string & xmlStr)
857  {
858  boost::property_tree::read_xml(xmlStr, pt);
859  parseGraph();
860  }
861 
862  template<typename TypeX, typename TypeY, typename TypeZ, typename TypeUnaligned>
863  JointModel MjcfGraph::createJoint(const Eigen::Vector3d & axis)
864  {
865  if (axis.isApprox(Eigen::Vector3d::UnitX()))
866  return TypeX();
867  else if (axis.isApprox(Eigen::Vector3d::UnitY()))
868  return TypeY();
869  else if (axis.isApprox(Eigen::Vector3d::UnitZ()))
870  return TypeZ();
871  else
872  return TypeUnaligned(axis.normalized());
873  }
874 
876  const MjcfJoint & joint, const MjcfBody & currentBody, SE3 & bodyInJoint)
877  {
878 
879  FrameIndex parentFrameId = 0;
880  if (!currentBody.bodyParent.empty())
881  parentFrameId = urdfVisitor.getBodyId(currentBody.bodyParent);
882 
883  // get body pose in body parent
884  const SE3 bodyPose = currentBody.bodyPlacement;
885  Inertia inert = currentBody.bodyInertia;
886  SE3 jointInParent = bodyPose * joint.jointPlacement;
887  bodyInJoint = joint.jointPlacement.inverse();
888  UrdfVisitor::JointType jType;
889 
890  RangeJoint range;
891  if (joint.jointType == "free")
892  {
893  urdfVisitor << "Free Joint " << '\n';
894  range = joint.range.setDimension<7, 6>();
895  jType = UrdfVisitor::FLOATING;
896  }
897  else if (joint.jointType == "slide")
898  {
899  urdfVisitor << "joint prismatic with axis " << joint.axis << '\n';
900  range = joint.range;
901  jType = UrdfVisitor::PRISMATIC;
902  }
903  else if (joint.jointType == "ball")
904  {
905  urdfVisitor << "Sphere Joint " << '\n';
906  range = joint.range.setDimension<4, 3>();
907  jType = UrdfVisitor::SPHERICAL;
908  }
909  else if (joint.jointType == "hinge")
910  {
911  urdfVisitor << "joint revolute with axis " << joint.axis << '\n';
912  range = joint.range;
913  jType = UrdfVisitor::REVOLUTE;
914  }
915  else
916  throw std::invalid_argument("Unknown joint type");
917 
918  urdfVisitor.addJointAndBody(
919  jType, joint.axis, parentFrameId, jointInParent, joint.jointName, inert, bodyInJoint,
920  currentBody.bodyName, range.maxEffort, range.maxVel, range.minConfig, range.maxConfig,
921  range.friction, range.damping);
922 
923  // Add armature info
924  JointIndex j_id = urdfVisitor.getJointId(joint.jointName);
925  urdfVisitor.model.armature.segment(
926  urdfVisitor.model.joints[j_id].idx_v(), urdfVisitor.model.joints[j_id].nv()) =
927  range.armature;
928  }
929 
930  void MjcfGraph::fillModel(const std::string & nameOfBody)
931  {
932  typedef UrdfVisitor::SE3 SE3;
933 
934  MjcfBody currentBody = mapOfBodies.at(nameOfBody);
935 
936  // get parent body frame
937  FrameIndex parentFrameId = 0;
938  if (!currentBody.bodyParent.empty())
939  parentFrameId = urdfVisitor.getBodyId(currentBody.bodyParent);
940 
941  Frame frame = urdfVisitor.model.frames[parentFrameId];
942  // get body pose in body parent
943  const SE3 bodyPose = currentBody.bodyPlacement;
944  Inertia inert = currentBody.bodyInertia;
945 
946  // Fixed Joint
947  if (currentBody.jointChildren.size() == 0)
948  {
949  if (currentBody.bodyParent.empty())
950  return;
951 
952  std::string jointName = nameOfBody + "_fixed";
953  urdfVisitor << jointName << " being parsed." << '\n';
954 
955  urdfVisitor.addFixedJointAndBody(parentFrameId, bodyPose, jointName, inert, nameOfBody);
956  return;
957  }
958 
959  bool composite = false;
960  SE3 jointPlacement, firstJointPlacement, prevJointPlacement = SE3::Identity();
961 
962  RangeJoint rangeCompo;
963  JointModelComposite jointM;
964  std::string jointName;
965 
966  if (currentBody.jointChildren.size() > 1)
967  {
968  composite = true;
969 
970  MjcfJoint firstOne = currentBody.jointChildren.at(0);
971  jointName = "Composite_" + firstOne.jointName;
972  }
973 
974  fillReferenceConfig(currentBody);
975 
976  bool isFirst = true;
977  SE3 bodyInJoint;
978 
979  if (!composite)
980  {
981  addSoloJoint(currentBody.jointChildren.at(0), currentBody, bodyInJoint);
982  }
983  else
984  {
985  for (const auto & joint : currentBody.jointChildren)
986  {
987  if (joint.jointType == "free")
988  throw std::invalid_argument("Joint Composite trying to be created with a freeFlyer");
989 
990  SE3 jointInParent = bodyPose * joint.jointPlacement;
991  bodyInJoint = joint.jointPlacement.inverse();
992  if (isFirst)
993  {
994  firstJointPlacement = jointInParent;
995  jointPlacement = SE3::Identity();
996  isFirst = false;
997  }
998  else
999  jointPlacement = prevJointPlacement.inverse() * jointInParent;
1000  if (joint.jointType == "slide")
1001  {
1002  jointM.addJoint(
1003  createJoint<JointModelPX, JointModelPY, JointModelPZ, JointModelPrismaticUnaligned>(
1004  joint.axis),
1005  jointPlacement);
1006 
1007  rangeCompo = rangeCompo.concatenate<1, 1>(joint.range);
1008  }
1009  else if (joint.jointType == "ball")
1010  {
1011  jointM.addJoint(JointModelSpherical(), jointPlacement);
1012  rangeCompo = rangeCompo.concatenate<4, 3>(joint.range.setDimension<4, 3>());
1013  }
1014  else if (joint.jointType == "hinge")
1015  {
1016  jointM.addJoint(
1017  createJoint<JointModelRX, JointModelRY, JointModelRZ, JointModelRevoluteUnaligned>(
1018  joint.axis),
1019  jointPlacement);
1020  rangeCompo = rangeCompo.concatenate<1, 1>(joint.range);
1021  }
1022  else
1023  throw std::invalid_argument("Unknown joint type trying to be parsed.");
1024 
1025  prevJointPlacement = jointInParent;
1026  }
1028 
1029  joint_id = urdfVisitor.model.addJoint(
1030  frame.parentJoint, jointM, frame.placement * firstJointPlacement, jointName,
1031  rangeCompo.maxEffort, rangeCompo.maxVel, rangeCompo.minConfig, rangeCompo.maxConfig,
1032  rangeCompo.friction, rangeCompo.damping);
1033  FrameIndex jointFrameId = urdfVisitor.model.addJointFrame(joint_id, (int)parentFrameId);
1034  urdfVisitor.appendBodyToJoint(jointFrameId, inert, bodyInJoint, nameOfBody);
1035 
1036  urdfVisitor.model.armature.segment(
1037  urdfVisitor.model.joints[joint_id].idx_v(), urdfVisitor.model.joints[joint_id].nv()) =
1038  rangeCompo.armature;
1039  }
1040 
1041  FrameIndex previousFrameId = urdfVisitor.model.frames.size();
1042  for (const auto & site : currentBody.siteChildren)
1043  {
1044  SE3 placement = bodyInJoint * site.sitePlacement;
1045  previousFrameId = urdfVisitor.model.addFrame(
1046  Frame(site.siteName, frame.parentJoint, previousFrameId, placement, OP_FRAME));
1047  }
1048  }
1049 
1050  void MjcfGraph::fillReferenceConfig(const MjcfBody & currentBody)
1051  {
1052  for (const auto & joint : currentBody.jointChildren)
1053  {
1054  if (joint.jointType == "free")
1055  {
1056  referenceConfig.conservativeResize(referenceConfig.size() + 7);
1057  referenceConfig.tail(7) << Eigen::Matrix<double, 7, 1>::Zero();
1058  }
1059  else if (joint.jointType == "ball")
1060  {
1061  referenceConfig.conservativeResize(referenceConfig.size() + 4);
1062  referenceConfig.tail(4) << Eigen::Vector4d::Zero();
1063  }
1064  else if (joint.jointType == "slide" || joint.jointType == "hinge")
1065  {
1066  referenceConfig.conservativeResize(referenceConfig.size() + 1);
1067  referenceConfig.tail(1) << joint.posRef;
1068  }
1069  }
1070  }
1071 
1072  void MjcfGraph::addKeyFrame(const Eigen::VectorXd & keyframe, const std::string & keyName)
1073  {
1074  // Check config vectors and add them if size is right
1075  const int model_nq = urdfVisitor.model.nq;
1076  if (keyframe.size() == model_nq)
1077  {
1078  Eigen::VectorXd qpos(model_nq);
1079  for (std::size_t i = 1; i < urdfVisitor.model.joints.size(); i++)
1080  {
1081  const auto & joint = urdfVisitor.model.joints[i];
1082  int idx_q = joint.idx_q();
1083  int nq = joint.nq();
1084 
1085  Eigen::VectorXd qpos_j = keyframe.segment(idx_q, nq);
1086  Eigen::VectorXd q_ref = referenceConfig.segment(idx_q, nq);
1087  if (joint.shortname() == "JointModelFreeFlyer")
1088  {
1089  Eigen::Vector4d new_quat(qpos_j(4), qpos_j(5), qpos_j(6), qpos_j(3));
1090  qpos_j.tail(4) = new_quat;
1091  }
1092  else if (joint.shortname() == "JointModelSpherical")
1093  {
1094  Eigen::Vector4d new_quat(qpos_j(1), qpos_j(2), qpos_j(3), qpos_j(0));
1095  qpos_j = new_quat;
1096  }
1097  else if (joint.shortname() == "JointModelComposite")
1098  {
1099  for (const auto & joint_ : boost::get<JointModelComposite>(joint.toVariant()).joints)
1100  {
1101  int idx_q_ = joint_.idx_q() - idx_q;
1102  int nq_ = joint_.nq();
1103  if (joint_.shortname() == "JointModelSpherical")
1104  {
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;
1108  }
1109  else
1110  qpos_j.segment(idx_q_, nq_) -= q_ref.segment(idx_q_, nq_);
1111  }
1112  }
1113  else
1114  qpos_j -= q_ref;
1115 
1116  qpos.segment(idx_q, nq) = qpos_j;
1117  }
1118 
1119  urdfVisitor.model.referenceConfigurations.insert(std::make_pair(keyName, qpos));
1120  }
1121  else
1122  throw std::invalid_argument("Keyframe size does not match model size");
1123  }
1124 
1126  const Model & model,
1128  {
1129  for (const auto & entry : mapOfEqualities)
1130  {
1131  const MjcfEquality & eq = entry.second;
1132 
1133  SE3 jointPlacement;
1134  jointPlacement.setIdentity();
1135  jointPlacement.translation() = eq.anchor;
1136 
1137  // Get Joint Indices from the model
1138  const JointIndex body1 = urdfVisitor.getParentId(eq.body1);
1139 
1140  // when body2 is not specified, we link to the world
1141  if (eq.body2 == "")
1142  {
1143  RigidConstraintModel rcm(CONTACT_3D, model, body1, jointPlacement, LOCAL);
1144  contact_models.push_back(rcm);
1145  }
1146  else
1147  {
1148  const JointIndex body2 = urdfVisitor.getParentId(eq.body2);
1150  CONTACT_3D, model, body1, jointPlacement, body2, jointPlacement.inverse(), LOCAL);
1151  contact_models.push_back(rcm);
1152  }
1153  }
1154  }
1155 
1157  {
1158  urdfVisitor.setName(modelName);
1159 
1160  // get name and inertia of first root link
1161  std::string rootLinkName = bodiesList.at(0);
1162  MjcfBody rootBody = mapOfBodies.find(rootLinkName)->second;
1163  if (rootBody.jointChildren.size() == 0)
1164  urdfVisitor.addRootJoint(rootBody.bodyInertia, rootLinkName);
1165 
1166  fillReferenceConfig(rootBody);
1167  for (const auto & entry : bodiesList)
1168  {
1169  fillModel(entry);
1170  }
1171 
1172  for (const auto & entry : mapOfConfigs)
1173  {
1174  addKeyFrame(entry.second, entry.first);
1175  }
1176  }
1177  } // namespace details
1178  } // namespace mjcf
1179 } // namespace pinocchio
meshcat-viewer.mesh
mesh
Definition: meshcat-viewer.py:54
ax
ax
pinocchio::mjcf::details::MjcfEquality::type
std::string type
Definition: mjcf-graph.hpp:351
pinocchio::InertiaTpl< context::Scalar, context::Options >
pinocchio::mjcf::details::MjcfCompiler::angle_converter
double angle_converter
Definition: mjcf-graph.hpp:53
pinocchio::FrameIndex
Index FrameIndex
Definition: multibody/fwd.hpp:28
common_symbols.type
type
Definition: common_symbols.py:35
pinocchio::mjcf::details::MjcfJoint::goThroughElement
void goThroughElement(const ptree &el, bool use_limits, const MjcfCompiler &currentCompiler)
Go through a joint node (default class or not) and parse info into the structure.
Definition: mjcf-graph.cpp:170
quadrotor-ocp.path
string path
Definition: quadrotor-ocp.py:11
pinocchio::mjcf::details::MjcfCompiler::mapEulerAngles
Eigen::Matrix3d mapEulerAngles
Definition: mjcf-graph.hpp:55
pinocchio::mjcf::details::MjcfClass
Structure to stock all default classes information.
Definition: mjcf-graph.hpp:77
pinocchio::mjcf::details::RangeJoint::setDimension
RangeJoint setDimension() const
Set dimension to the limits to match the joint nq and nv.
Definition: mjcf-graph.cpp:118
pinocchio::mjcf::details::MjcfGraph::mapOfTextures
TextureMap_t mapOfTextures
Definition: mjcf-graph.hpp:403
pinocchio::mjcf::details::MjcfCompiler
Informations that are stocked in the XML tag compile.
Definition: mjcf-graph.hpp:39
pinocchio::mjcf::details::MjcfGraph::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:382
pinocchio::SE3Tpl::inverse
SE3Tpl inverse() const
aXb = bXa.inverse()
Definition: spatial/se3-tpl.hpp:149
pinocchio::mjcf::details::MjcfCompiler::boundInertia
double boundInertia
Definition: mjcf-graph.hpp:60
pinocchio::mjcf::details::MjcfTexture::textType
std::string textType
Definition: mjcf-graph.hpp:218
pinocchio::idx_q
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
pinocchio::mjcf::details::MjcfJoint::fill
void fill(const ptree &el, const MjcfBody &currentBody, const MjcfGraph &currentGraph)
Definition: mjcf-graph.cpp:235
pinocchio::mjcf::details::MjcfBody::bodyInertia
Inertia bodyInertia
Definition: mjcf-graph.hpp:105
pinocchio::mjcf::details::MjcfGraph::referenceConfig
Eigen::VectorXd referenceConfig
Definition: mjcf-graph.hpp:410
pinocchio::mjcf::details::MjcfMesh
All informations related to a mesh are stored here.
Definition: mjcf-graph.hpp:206
lambdas.parent
parent
Definition: lambdas.py:21
pinocchio::mjcf::details::MjcfCompiler::convertAngle
double convertAngle(const double &angle_) const
Convert the angle in radian if model was declared to use degree.
Definition: mjcf-graph.cpp:100
quat
quat
pinocchio::mjcf::details::MjcfGraph::mapOfClasses
ClassMap_t mapOfClasses
Definition: mjcf-graph.hpp:395
pinocchio::mjcf::details::RangeJoint::maxConfig
Eigen::VectorXd maxConfig
Definition: mjcf-graph.hpp:123
pinocchio::mjcf::details::MjcfEquality::anchor
Eigen::Vector3d anchor
Definition: mjcf-graph.hpp:366
pinocchio::mjcf::details::RangeJoint
All joint limits.
Definition: mjcf-graph.hpp:116
pinocchio::mjcf::details::MjcfGraph::mapOfEqualities
EqualityMap_t mapOfEqualities
Definition: mjcf-graph.hpp:407
pinocchio::mjcf::details::UrdfVisitor
pinocchio::urdf::details::UrdfVisitor< double, 0, ::pinocchio::JointCollectionDefaultTpl > UrdfVisitor
Definition: mjcf-graph.cpp:18
pinocchio::mjcf::details::RangeJoint::maxVel
Eigen::VectorXd maxVel
Definition: mjcf-graph.hpp:121
pinocchio::Inertia
InertiaTpl< context::Scalar, context::Options > Inertia
Definition: spatial/fwd.hpp:69
pinocchio::SE3Tpl< context::Scalar, context::Options >
pinocchio::mjcf::details::MjcfGraph::parseRootTree
void parseRootTree()
Fill the pinocchio model with all the infos from the graph.
Definition: mjcf-graph.cpp:1156
pinocchio::nq
int nq(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNqVisitor to get the dimension of the joint configuration space.
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:17
pinocchio::name
std::string name(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the name of it.
mjcf-graph.hpp
model.hpp
simulation-closed-kinematic-chains.rotation
rotation
Definition: simulation-closed-kinematic-chains.py:26
pinocchio::mjcf::details::MjcfTexture::gridsize
Eigen::Vector2d gridsize
Definition: mjcf-graph.hpp:222
pinocchio::mjcf::details::MjcfGeom
Definition: mjcf-graph.hpp:247
pinocchio::JointModelSpherical
JointModelSphericalTpl< context::Scalar > JointModelSpherical
Definition: multibody/joint/fwd.hpp:73
pinocchio::mjcf::details::MjcfEquality::body1
std::string body1
Definition: mjcf-graph.hpp:360
pinocchio::mjcf::details::MjcfCompiler::inertiafromgeom
boost::logic::tribool inertiafromgeom
Definition: mjcf-graph.hpp:63
pinocchio::mjcf::details::MjcfCompiler::convertEuler
Eigen::Matrix3d convertEuler(const Eigen::Vector3d &angles) const
Convert the euler angles according to the convention declared in the compile tag.
Definition: mjcf-graph.cpp:105
pinocchio::mjcf::details::MjcfJoint
All joint information parsed from the mjcf model.
Definition: mjcf-graph.hpp:174
pinocchio::mjcf::details::RangeJoint::minConfig
Eigen::VectorXd minConfig
Definition: mjcf-graph.hpp:125
R
R
pinocchio::mjcf::details::RangeJoint::concatenate
RangeJoint concatenate(const RangeJoint &range) const
Concatenate 2 rangeJoint.
Definition: mjcf-graph.cpp:138
pinocchio::mjcf::details::MjcfMaterial
All informations related to material are stored here.
Definition: mjcf-graph.hpp:226
pinocchio::mjcf::details::MjcfGraph::parseJointAndBody
void parseJointAndBody(const ptree &el, const boost::optional< std::string > &childClass, const std::string &parentName="")
Go through the main body of the mjcf file "worldbody" to get all the info ready to create the model.
Definition: mjcf-graph.cpp:404
pinocchio::mjcf::details::MjcfClass::className
std::string className
Definition: mjcf-graph.hpp:83
pinocchio::mjcf::details::MjcfGraph::modelName
std::string modelName
Definition: mjcf-graph.hpp:419
pinocchio::mjcf::details::RangeJoint::friction
Eigen::VectorXd friction
Definition: mjcf-graph.hpp:133
pinocchio::mjcf::details::MjcfCompiler::boundMass
double boundMass
Definition: mjcf-graph.hpp:58
pinocchio::mjcf::details::MjcfJoint::axis
Eigen::Vector3d axis
Definition: mjcf-graph.hpp:185
pinocchio::mjcf::details::MjcfJoint::jointType
std::string jointType
Definition: mjcf-graph.hpp:190
pinocchio::JointModelCompositeTpl::addJoint
JointModelDerived & addJoint(const JointModelBase< JointModel > &jmodel, const SE3 &placement=SE3::Identity())
Add a joint to the vector of joints.
Definition: joint-composite.hpp:278
pinocchio::mjcf::details::MjcfGraph::convertInertiaFromMjcf
Inertia convertInertiaFromMjcf(const ptree &el) const
Convert Inertia of an mjcf element into Inertia model of pinocchio.
Definition: mjcf-graph.cpp:356
pinocchio::mjcf::details::copyPtree
static void copyPtree(const ptree &src, ptree &dst)
Copy the value of ptree src into dst.
Definition: mjcf-graph.cpp:26
pinocchio::FrameTpl
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Definition: multibody/frame.hpp:55
pinocchio::Index
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
Definition: multibody/fwd.hpp:22
pinocchio::mjcf::details::MjcfGraph::parseGraphFromXML
void parseGraphFromXML(const std::string &xmlStr)
parse the mjcf file into a graph
Definition: mjcf-graph.cpp:856
pinocchio::mjcf::details::MjcfGraph::mapOfConfigs
ConfigMap_t mapOfConfigs
Definition: mjcf-graph.hpp:405
pinocchio::SE3Tpl::translation
ConstLinearRef translation() const
Definition: se3-base.hpp:52
pinocchio::InertiaTpl< context::Scalar, context::Options >::Zero
static InertiaTpl Zero()
Definition: spatial/inertia.hpp:337
pinocchio::mjcf::details::MjcfGraph::parseEquality
void parseEquality(const ptree &el)
Parse all the info from the equality tag.
Definition: mjcf-graph.cpp:764
pinocchio::mjcf::details::MjcfClass::classElement
ptree classElement
Definition: mjcf-graph.hpp:85
pinocchio::mjcf::details::MjcfBody::geomChildren
std::vector< MjcfGeom > geomChildren
Definition: mjcf-graph.hpp:110
pinocchio::mjcf::details::MjcfGraph::parseTexture
void parseTexture(const ptree &el)
Parse all the info from a texture node.
Definition: mjcf-graph.cpp:510
pinocchio::mjcf::details::RangeJoint::springReference
Eigen::VectorXd springReference
Definition: mjcf-graph.hpp:130
details
pinocchio::mjcf::details::MjcfJoint::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:177
pinocchio::placement
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & placement
Definition: spatial/classic-acceleration.hpp:122
pinocchio::mjcf::details::RangeJoint::damping
Eigen::VectorXd damping
Definition: mjcf-graph.hpp:135
pinocchio::RigidConstraintModelTpl
Definition: algorithm/constraints/fwd.hpp:14
pinocchio::mjcf::details::MjcfTexture::filePath
std::string filePath
Definition: mjcf-graph.hpp:220
filename
filename
pinocchio::mjcf::details::MjcfGraph::parseCompiler
void parseCompiler(const ptree &el)
Parse all the info from the compile node into compilerInfo.
Definition: mjcf-graph.cpp:651
pinocchio::JointModelTpl< context::Scalar >
mat
mat
pinocchio::SE3Tpl::rotation
ConstAngularRef rotation() const
Definition: se3-base.hpp:48
pinocchio::mjcf::details::MjcfGraph::fillModel
void fillModel(const std::string &nameOfBody)
Use all the infos that were parsed from the xml file to add a body and joint to the model.
Definition: mjcf-graph.cpp:930
value
float value
pinocchio::mjcf::details::ELEMENTS
static const std::array< std::string, 3 > ELEMENTS
Definition: mjcf-graph.cpp:21
pinocchio::mjcf::details::MjcfGraph::parseContactInformation
void parseContactInformation(const Model &model, PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) &contact_models)
Parse the equality constraints and add them to the model.
Definition: mjcf-graph.cpp:1125
pinocchio::mjcf::details::MjcfGraph::bodiesList
VectorOfStrings bodiesList
Definition: mjcf-graph.hpp:416
pinocchio::mjcf::details::RangeJoint::springStiffness
Eigen::VectorXd springStiffness
Definition: mjcf-graph.hpp:128
pinocchio::mjcf::details::MjcfBody::siteChildren
std::vector< MjcfSite > siteChildren
Definition: mjcf-graph.hpp:112
pinocchio::mjcf::details::MjcfGraph::addKeyFrame
void addKeyFrame(const Eigen::VectorXd &keyframe, const std::string &keyName)
Add a keyframe to the model (ie reference configuration)
Definition: mjcf-graph.cpp:1072
pinocchio::mjcf::details::MjcfGraph::parseDefault
void parseDefault(ptree &el, const ptree &parent, const std::string &parentTag)
Go through the default part of the file and get all the class name. Fill the mapOfDefault for later u...
Definition: mjcf-graph.cpp:619
pos
pos
pinocchio::mjcf::details::MjcfGraph::parseMesh
void parseMesh(const ptree &el)
Parse all the info from a mesh node.
Definition: mjcf-graph.cpp:579
pinocchio::mjcf::details::MjcfGraph::mapOfMeshes
MeshMap_t mapOfMeshes
Definition: mjcf-graph.hpp:401
pinocchio::mjcf::details::MjcfJoint::jointPlacement
SE3 jointPlacement
Definition: mjcf-graph.hpp:182
pinocchio::mjcf::details::MjcfGraph::mapOfBodies
BodyMap_t mapOfBodies
Definition: mjcf-graph.hpp:397
pinocchio::context::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: context/generic.hpp:53
pinocchio::mjcf::details::MjcfGraph::parseMaterial
void parseMaterial(const ptree &el)
Parse all the info from a material node.
Definition: mjcf-graph.cpp:548
axis
axis
pinocchio::mjcf::details::RangeJoint::frictionLoss
double frictionLoss
Definition: mjcf-graph.hpp:140
pinocchio::mjcf::details::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.cpp:15
contact-cholesky.frame
frame
Definition: contact-cholesky.py:24
pinocchio::mjcf::details::MjcfGraph::parseKeyFrame
void parseKeyFrame(const ptree &el)
Parse all the info from the meta tag keyframe.
Definition: mjcf-graph.cpp:743
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR
#define PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(T)
Definition: container/aligned-vector.hpp:13
meshcat-viewer-solo.q_ref
q_ref
Definition: meshcat-viewer-solo.py:26
pinocchio::Frame
FrameTpl< context::Scalar, context::Options > Frame
Definition: multibody/fwd.hpp:31
anymal-simulation.mass
mass
Definition: anymal-simulation.py:62
pinocchio::mjcf::details::MjcfGeom::fill
void fill(const ptree &el, const MjcfBody &currentBody, const MjcfGraph &currentGraph)
Fill Geometry element with info from ptree nodes.
Definition: mjcf-graph-geom.cpp:403
value_type
Scalar value_type
Definition: eigen_plugin.hpp:2
pinocchio::mjcf::details::MjcfJoint::jointName
std::string jointName
Definition: mjcf-graph.hpp:180
pinocchio::mjcf::details::MjcfBody::bodyClassName
std::string bodyClassName
Definition: mjcf-graph.hpp:97
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1084
pinocchio::mjcf::details::MjcfGraph::mapOfMaterials
MaterialMap_t mapOfMaterials
Definition: mjcf-graph.hpp:399
pinocchio::mjcf::details::MjcfCompiler::meshdir
std::string meshdir
Definition: mjcf-graph.hpp:48
pinocchio::mjcf::details::MjcfCompiler::texturedir
std::string texturedir
Definition: mjcf-graph.hpp:50
pinocchio::JointModelCompositeTpl
Definition: multibody/joint/fwd.hpp:141
pinocchio::mjcf::details::MjcfGraph::fillReferenceConfig
void fillReferenceConfig(const MjcfBody &currentBody)
Fill reference configuration for a body and all it's associated dof.
Definition: mjcf-graph.cpp:1050
pinocchio::OP_FRAME
@ OP_FRAME
operational frame: user-defined frames that are defined at runtime
Definition: multibody/frame.hpp:33
pinocchio::mjcf::details::MjcfGraph::urdfVisitor
UrdfVisitor & urdfVisitor
Definition: mjcf-graph.hpp:426
pinocchio::mjcf::details::MjcfGraph::parseGraph
void parseGraph()
parse the mjcf file into a graph
Definition: mjcf-graph.cpp:811
pinocchio::mjcf::details::MjcfGraph::compilerInfo
MjcfCompiler compilerInfo
Definition: mjcf-graph.hpp:393
pinocchio::mjcf::details::MjcfGraph::pt
ptree pt
Definition: mjcf-graph.hpp:413
pinocchio::mjcf::details::MjcfEquality::name
std::string name
Definition: mjcf-graph.hpp:348
pinocchio::mjcf::details::MjcfCompiler::autolimits
bool autolimits
Definition: mjcf-graph.hpp:43
pinocchio::mjcf::details::MjcfCompiler::strippath
bool strippath
Definition: mjcf-graph.hpp:46
pinocchio::mjcf::details::MjcfGraph::parseAsset
void parseAsset(const ptree &el)
Parse all the info from the meta tag asset (mesh, material, texture)
Definition: mjcf-graph.cpp:601
pinocchio::mjcf::details::MjcfGraph::convertPosition
SE3 convertPosition(const ptree &el) const
Convert pose of an mjcf element into SE3.
Definition: mjcf-graph.cpp:285
pinocchio::SE3Tpl::Identity
static SE3Tpl Identity()
Definition: spatial/se3-tpl.hpp:136
pinocchio::mjcf::details::MjcfGraph::addSoloJoint
void addSoloJoint(const MjcfJoint &jointInfo, const MjcfBody &currentBody, SE3 &bodyInJoint)
Add a joint to the model. only needed when a body has a solo joint child.
Definition: mjcf-graph.cpp:875
pinocchio::mjcf::details::updatePath
static boost::filesystem::path updatePath(bool strippath, const std::string &dir, const std::string &modelPath, const boost::filesystem::path &filePath)
Definition: mjcf-graph.cpp:72
pinocchio::mjcf::details::MjcfBody::bodyName
std::string bodyName
Definition: mjcf-graph.hpp:93
pinocchio::mjcf::details::updateClassElement
static void updateClassElement(ptree &current, const ptree &parent)
Update class Element in order to have all info of parent classes.
Definition: mjcf-graph.cpp:35
pinocchio::mjcf::details::MjcfJoint::posRef
double posRef
Definition: mjcf-graph.hpp:192
pinocchio::mjcf::details::MjcfBody::bodyParent
std::string bodyParent
Definition: mjcf-graph.hpp:95
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
pinocchio::mjcf::details::MjcfGraph
The graph which contains all information taken from the mjcf file.
Definition: mjcf-graph.hpp:379
pinocchio::mjcf::details::MjcfBody::jointChildren
std::vector< MjcfJoint > jointChildren
Definition: mjcf-graph.hpp:108
pinocchio::mjcf::details::RangeJoint::armature
Eigen::VectorXd armature
Definition: mjcf-graph.hpp:138
pinocchio::mjcf::details::MjcfBody
All Bodies informations extracted from mjcf model.
Definition: mjcf-graph.hpp:89
pinocchio::mjcf::details::MjcfEquality
Definition: mjcf-graph.hpp:343
pinocchio::mjcf::details::internal::getConfiguredStringStream
std::istringstream getConfiguredStringStream(const std::string &str)
Definition: mjcf-graph.hpp:547
pinocchio::mjcf::details::MjcfSite
Definition: mjcf-graph.hpp:317
contact-cholesky.contact_models
list contact_models
Definition: contact-cholesky.py:22
pinocchio::mjcf::details::MjcfEquality::body2
std::string body2
Definition: mjcf-graph.hpp:362
pinocchio::mjcf::details::MjcfBody::bodyPlacement
SE3 bodyPlacement
Definition: mjcf-graph.hpp:103
contact-info.hpp
pinocchio::python::context::SE3
SE3Tpl< Scalar, Options > SE3
Definition: bindings/python/context/generic.hpp:53
pinocchio::SE3
SE3Tpl< context::Scalar, context::Options > SE3
Definition: spatial/fwd.hpp:64
append-urdf-model-with-another-model.joint_id
joint_id
Definition: append-urdf-model-with-another-model.py:34
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::mjcf::details::MjcfGraph::createJoint
JointModel createJoint(const Eigen::Vector3d &axis)
Create a joint to add to the joint composite if needed.
Definition: mjcf-graph.cpp:863
pinocchio::CONTACT_3D
@ CONTACT_3D
Definition: algorithm/contact-info.hpp:21
pinocchio::mjcf::details::MjcfBody::childClass
std::string childClass
Definition: mjcf-graph.hpp:100
CppAD::max
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
Definition: autodiff/cppad.hpp:181
pinocchio::SE3Tpl::setIdentity
SE3Tpl & setIdentity()
Definition: spatial/se3-tpl.hpp:141
pinocchio::mjcf::details::getName
static std::string getName(const ptree &el, const boost::filesystem::path &filePath)
Definition: mjcf-graph.cpp:54
d
FCL_REAL d
pinocchio::mjcf::details::internal::getUnknownSizeVectorFromStream
Eigen::VectorXd getUnknownSizeVectorFromStream(const std::string &str)
Definition: mjcf-graph.hpp:565
n
Vec3f n
robot-wrapper-viewer.com
com
Definition: robot-wrapper-viewer.py:45
pinocchio::mjcf::details::RangeJoint::maxEffort
Eigen::VectorXd maxEffort
Definition: mjcf-graph.hpp:119
pinocchio::mjcf::details::MjcfTexture
All informations related to a texture are stored here.
Definition: mjcf-graph.hpp:215
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio::mjcf::details::MjcfGraph::modelPath
std::string modelPath
Definition: mjcf-graph.hpp:420
pinocchio::mjcf::details::MjcfSite::fill
void fill(const ptree &el, const MjcfBody &currentBody, const MjcfGraph &currentGraph)
Definition: mjcf-graph-geom.cpp:473
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::mjcf::details::MjcfGeom::VISUAL
@ VISUAL
Definition: mjcf-graph.hpp:255
pinocchio::mjcf::details::MjcfJoint::range
RangeJoint range
Definition: mjcf-graph.hpp:187
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:31