mjcf-graph-geom.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2016-2024 CNRS INRIA
3 //
4 
6 #ifdef PINOCCHIO_WITH_HPP_FCL
7 
10 
11 #endif // PINOCCHIO_WITH_HPP_FCL
12 
13 namespace pinocchio
14 {
15  namespace mjcf
16  {
17  namespace details
18  {
19  static double computeVolume(const Eigen::VectorXd & size, const std::string & geomType)
20  {
21  double pi = boost::math::constants::pi<double>();
22  if (geomType == "box")
23  {
24  return size.prod();
25  }
26  else if (geomType == "cylinder")
27  {
28  return 2 * pi * std::pow(size(0), 2) * size(1);
29  }
30  else if (geomType == "sphere")
31  {
32  return 4.0 / 3 * pi * std::pow(size(0), 3);
33  }
34  else if (geomType == "capsule")
35  {
36  return 4.0 / 3 * pi * std::pow(size(0), 3) + 2 * pi * std::pow(size(0), 2) * size(1);
37  }
38  else if (geomType == "ellipsoid")
39  {
40  return 4.0 / 3 * pi * size.prod();
41  }
42  else
43  {
44  throw std::invalid_argument("geometry type does not exist");
45  }
46  }
47 
48  bool isType(const MjcfGeom & geom, const GeometryType & type)
49  {
50  switch (type)
51  {
53  return geom.geomKind != MjcfGeom::VISUAL;
54  default:
56  return geom.geomKind != MjcfGeom::COLLISION;
57  }
58  }
59 
67 #ifdef PINOCCHIO_WITH_HPP_FCL
68  static std::shared_ptr<fcl::CollisionGeometry> retrieveCollisionGeometry(
69  ::hpp::fcl::MeshLoaderPtr & meshLoader,
70  const MjcfGeom & geom,
71  const MjcfGraph & currentGraph,
72  std::string & meshPath,
73  Eigen::Vector3d & meshScale)
74  {
75  if (geom.geomType == "mesh")
76  {
77  MjcfMesh currentMesh = currentGraph.mapOfMeshes.at(geom.meshName);
78  meshPath = currentMesh.filePath;
79  meshScale = currentMesh.scale;
80  hpp::fcl::BVHModelPtr_t bvh = meshLoader->load(meshPath, meshScale);
81  return bvh;
82  }
83  else if (geom.geomType == "cylinder")
84  {
85  meshPath = "CYLINDER";
86  meshScale << 1, 1, 1;
87  double radius = geom.size(0);
88  double height = geom.size(1) * 2;
89  return std::make_shared<fcl::Cylinder>(radius, height);
90  }
91  else if (geom.geomType == "box")
92  {
93  meshPath = "BOX";
94  meshScale << 1, 1, 1;
95  double x = geom.size(0);
96  double y = geom.size(1);
97  double z = geom.size(2);
98  return std::make_shared<fcl::Box>(x, y, z);
99  }
100  else if (geom.geomType == "sphere")
101  {
102  meshPath = "SPHERE";
103  meshScale << 1, 1, 1;
104  double radius = geom.size(0);
105  return std::make_shared<fcl::Sphere>(radius);
106  }
107  else if (geom.geomType == "ellipsoid")
108  {
109  meshPath = "ELLIPSOID";
110  meshScale << 1, 1, 1;
111  double rx = geom.size(0);
112  double ry = geom.size(1);
113  double rz = geom.size(2);
114  return std::make_shared<fcl::Ellipsoid>(rx, ry, rz);
115  }
116  else if (geom.geomType == "capsule")
117  {
118  meshPath = "CAPSULE";
119  meshScale << 1, 1, 1;
120  double radius = geom.size(0);
121  double height = geom.size(1) * 2;
122  return std::make_shared<fcl::Capsule>(radius, height);
123  }
124  else
125  throw std::invalid_argument("Unknown geometry type :"); // Missing plane, hfield and sdf
126  }
127 #else
128  static std::shared_ptr<fcl::CollisionGeometry> retrieveCollisionGeometry(
129  ::hpp::fcl::MeshLoaderPtr &,
130  const MjcfGeom &,
131  const MjcfGraph &,
132  std::string &,
133  Eigen::Vector3d &)
134  {
135  return std::make_shared<fcl::CollisionGeometry>();
136  }
137 #endif
138 
144  static void addLinksToGeomModel(
145  const MjcfBody & currentBody,
146  const MjcfGraph & currentGraph,
147  GeometryModel & geomModel,
148  ::hpp::fcl::MeshLoaderPtr & meshLoader,
149  const GeometryType & type)
150  {
151  const std::string & bodyName = currentBody.bodyName;
152  FrameIndex frame_id = currentGraph.urdfVisitor.getBodyId(bodyName);
153  Frame frame = currentGraph.urdfVisitor.getBodyFrame(bodyName);
154 
155  const SE3 & bodyPlacement = frame.placement;
156 
157  std::size_t objectId = 0;
158  for (const auto & geom : currentBody.geomChildren)
159  {
160  std::string meshPath = "";
161  Eigen::Vector3d meshScale(Eigen::Vector3d::Ones());
162  if (isType(geom, type))
163  {
165  retrieveCollisionGeometry(meshLoader, geom, currentGraph, meshPath, meshScale);
166 
167  bool overrideMaterial = false;
168  Eigen::Vector4d meshColor = geom.rgba;
169  std::string texturePath;
170  if (!geom.materialName.empty())
171  {
172  MjcfMaterial mat = currentGraph.mapOfMaterials.at(geom.materialName);
173  meshColor = mat.rgba;
174  overrideMaterial = true;
175  if (!mat.texture.empty())
176  {
177  MjcfTexture text = currentGraph.mapOfTextures.at(mat.texture);
178  texturePath = text.filePath;
179  }
180  }
181  const SE3 geomPlacement = bodyPlacement * geom.geomPlacement;
182  std::ostringstream geometry_object_suffix;
183  geometry_object_suffix << "_" << objectId;
184  std::string geometry_object_name = std::string(bodyName + geometry_object_suffix.str());
185 
186  GeometryObject geometry_object(
187  geometry_object_name, frame.parentJoint, frame_id, geomPlacement, geometry, meshPath,
188  meshScale, overrideMaterial, meshColor, texturePath);
189  geomModel.addGeometryObject(geometry_object);
190  ++objectId;
191  }
192  }
193  }
194 
196  {
197  // texture name
198  auto text_s = el.get_optional<std::string>("<xmlattr>.texture");
199  if (text_s)
200  texture = *text_s;
201 
202  // Emission
203  auto single_v = el.get_optional<float>("<xmlattr>.emission");
204  if (single_v)
205  emission = *single_v;
206 
207  // Specular
208  if ((single_v = el.get_optional<float>("<xmlattr>.specular")))
209  specular = *single_v;
210 
211  // Shininess
212  if ((single_v = el.get_optional<float>("<xmlattr>.shininess")))
213  shininess = *single_v;
214 
215  if ((single_v = el.get_optional<float>("<xmlattr>.reflectance")))
216  reflectance = *single_v;
217 
218  auto rgba_ = el.get_optional<std::string>("<xmlattr>.rgba");
219  if (rgba_)
220  rgba = internal::getVectorFromStream<4>(*rgba_);
221  }
222 
223  void MjcfGeom::goThroughElement(const ptree & el, const MjcfGraph & currentGraph)
224  {
225  if (el.get_child_optional("<xmlattr>.pos") && el.get_child_optional("<xmlattr>.fromto"))
226  throw std::invalid_argument("Both pos and fromto are defined in geom object");
227 
228  // Placement
229  geomPlacement = currentGraph.convertPosition(el);
230 
231  // density
232  auto value_v = el.get_optional<double>("<xmlattr>.density");
233  if (value_v)
234  density = *value_v;
235 
236  // contype
237  auto val_v = el.get_optional<int>("<xmlattr>.contype");
238  if (val_v)
239  contype = *val_v;
240  // condim
241  if ((val_v = el.get_optional<int>("<xmlattr>.conaffinity")))
242  conaffinity = *val_v;
243  // group
244  if ((val_v = el.get_optional<int>("<xmlattr>.group")))
245  group = *val_v;
246 
247  // mass
248  massGeom = el.get_optional<double>("<xmlattr>.mass");
249 
250  // shellinertia
251  auto value_s = el.get_optional<std::string>("<xmlattr>.shellinertia");
252  if (value_s)
253  throw std::invalid_argument("Shell inertia computation is not supported yet.");
254 
255  // type
256  if ((value_s = el.get_optional<std::string>("<xmlattr>.type")))
257  geomType = *value_s;
258 
259  // material name
260  if ((value_s = el.get_optional<std::string>("<xmlattr>.material")))
261  materialName = *value_s;
262 
263  if (geomType == "mesh")
264  {
265  value_s = el.get_optional<std::string>("<xmlattr>.mesh");
266  if (value_s)
267  meshName = *value_s;
268  }
269 
270  // rgba
271  if ((value_s = el.get_optional<std::string>("<xmlattr>.rgba")))
272  rgba = internal::getVectorFromStream<4>(*value_s);
273 
274  // size
275  if ((value_s = el.get_optional<std::string>("<xmlattr>.size")))
276  sizeS = *value_s;
277  // fromto
278  if (!fromtoS)
279  fromtoS = el.get_optional<std::string>("<xmlattr>.fromto");
280  if (fromtoS)
281  {
282  Eigen::VectorXd poses = internal::getVectorFromStream<6>(*fromtoS);
283  geomPlacement.translation() = (poses.head(3) + poses.tail(3)) / 2;
284 
285  Eigen::Vector3d zaxis = poses.tail(3) - poses.head(3);
286  // Compute the rotation matrix that maps z_axis to unit z
288  Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitZ(), zaxis).toRotationMatrix();
289  }
290  }
291 
293  {
294  // Common mechanism to set visual only geometry
295  if (contype == 0 && conaffinity == 0)
296  geomKind = VISUAL;
297  else if (group > 2) // Mechanism for Collision only geometries
299  else
300  geomKind = BOTH;
301  }
302 
304  {
305  std::vector<std::string> forbiddenListFromTo = {"plane", "hfield", "mesh", "sphere"};
306  if (
307  fromtoS
308  && std::find(forbiddenListFromTo.begin(), forbiddenListFromTo.end(), geomType)
309  != forbiddenListFromTo.end())
310  throw std::invalid_argument(
311  "fromto tag can only be used with capsules, boxes, cylinders and ellipsoids");
312 
313  // First deal with cases that do not work with fromto
314  if (geomType == "sphere")
315  size = internal::getVectorFromStream<1>(sizeS);
316  else if (geomType == "plane")
317  size = internal::getVectorFromStream<3>(sizeS);
318  else if (geomType == "box")
319  {
320  if (!fromtoS)
321  size = internal::getVectorFromStream<3>(sizeS) * 2; // half x, half y, half z
322  else
323  {
324  size = Eigen::Vector3d::Zero();
325  size(0) = internal::getVectorFromStream<1>(sizeS)(0) * 2;
326  size(1) = size(0);
327  Eigen::VectorXd poses = internal::getVectorFromStream<6>(*fromtoS);
328  Eigen::Vector3d zaxis = poses.tail(3) - poses.head(3);
329  size(2) = zaxis.norm();
330  }
331  }
332  else if (geomType == "ellipsoid")
333  {
334  if (!fromtoS)
335  size = internal::getVectorFromStream<3>(sizeS); // radius and half length
336  else
337  {
338  size = Eigen::Vector3d::Zero();
339  size(0) = internal::getVectorFromStream<1>(sizeS)(0);
340  size(1) = size(0);
341  Eigen::VectorXd poses = internal::getVectorFromStream<6>(*fromtoS);
342  Eigen::Vector3d zaxis = poses.tail(3) - poses.head(3);
343  size(2) = zaxis.norm() / 2; // to get radius;
344  }
345  }
346  else if (geomType == "cylinder" || geomType == "capsule")
347  {
348  if (!fromtoS)
349  size = internal::getVectorFromStream<2>(sizeS);
350  else
351  {
352  size = Eigen::Vector2d::Zero();
353  size(0) = internal::getVectorFromStream<1>(sizeS)(0);
354  Eigen::VectorXd poses = internal::getVectorFromStream<6>(*fromtoS);
355  Eigen::Vector3d zaxis = poses.tail(3) - poses.head(3);
356  size(1) = zaxis.norm() / 2; // to get half height
357  }
358  }
359  else if (geomType == "mesh")
360  return;
361  else
362  throw std::invalid_argument("geomType does not exist");
363  }
364 
366  {
367  if (geomType == "mesh" || geomType == "plane" || geomType == "hfield")
368  return;
369 
370  double mass;
371  if (massGeom)
372  mass = *massGeom;
373  else
375 
376  if (geomType == "box")
377  {
379  }
380  else if (geomType == "cylinder")
381  {
383  }
384  else if (geomType == "ellipsoid")
385  {
387  }
388  else if (geomType == "sphere")
389  {
391  }
392  else if (geomType == "capsule")
393  {
395  }
396  else
397  {
398  throw std::invalid_argument("Unsupported geometry type");
399  }
400  }
401 
402  void
403  MjcfGeom::fill(const ptree & el, const MjcfBody & currentBody, const MjcfGraph & currentGraph)
404  {
405  // Name
406  auto name_s = el.get_optional<std::string>("<xmlattr>.name");
407  if (name_s)
408  geomName = *name_s;
409  else
410  geomName =
411  currentBody.bodyName + "Geom_" + std::to_string(currentBody.geomChildren.size());
412 
413  // ChildClass < Class < Real Joint
414  // childClass
415  if (currentBody.childClass != "")
416  {
417  const MjcfClass & classE = currentGraph.mapOfClasses.at(currentBody.childClass);
418  if (auto geom_p = classE.classElement.get_child_optional("geom"))
419  goThroughElement(*geom_p, currentGraph);
420  }
421 
422  // Class
423  auto cl_s = el.get_optional<std::string>("<xmlattr>.class");
424  if (cl_s)
425  {
426  std::string className = *cl_s;
427  const MjcfClass & classE = currentGraph.mapOfClasses.at(className);
428  if (auto geom_p = classE.classElement.get_child_optional("geom"))
429  goThroughElement(*geom_p, currentGraph);
430  }
431 
432  // Geom
433  goThroughElement(el, currentGraph);
434  if (geomType == "mesh" && meshName.empty())
435  throw std::invalid_argument("Type is mesh but no mesh file were provided");
436  // Compute Kind of geometry
437  findKind();
438 
439  computeSize();
440 
441  // Compute Mass and inertia of geom object
442  computeInertia();
443  }
444 
445  void MjcfSite::goThroughElement(const ptree & el, const MjcfGraph & currentGraph)
446  {
447  if (el.get_child_optional("<xmlattr>.pos") && el.get_child_optional("<xmlattr>.fromto"))
448  throw std::invalid_argument("Both pos and fromto are defined in site object");
449 
450  // Placement
451  sitePlacement = currentGraph.convertPosition(el);
452 
453  auto fromtoS = el.get_optional<std::string>("<xmlattr>.fromto");
454  if (fromtoS)
455  {
456  Eigen::VectorXd poses = internal::getVectorFromStream<6>(*fromtoS);
457  sitePlacement.translation() = (poses.head(3) + poses.tail(3)) / 2;
458 
459  Eigen::Vector3d zaxis = poses.tail(3) - poses.head(3);
460  // Compute the rotation matrix that maps z_axis to unit z
462  Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitZ(), zaxis).toRotationMatrix();
463  }
464  }
465 
466  void
467  MjcfSite::fill(const ptree & el, const MjcfBody & currentBody, const MjcfGraph & currentGraph)
468  {
469  // Name
470  auto name_s = el.get_optional<std::string>("<xmlattr>.name");
471  if (name_s)
472  siteName = *name_s;
473  else
474  siteName =
475  currentBody.bodyName + "Site_" + std::to_string(currentBody.siteChildren.size());
476 
477  // ChildClass < Class < Real Joint
478  // childClass
479  if (currentBody.childClass != "")
480  {
481  const MjcfClass & classE = currentGraph.mapOfClasses.at(currentBody.childClass);
482  if (auto site_p = classE.classElement.get_child_optional("site"))
483  goThroughElement(*site_p, currentGraph);
484  }
485 
486  // Class
487  auto cl_s = el.get_optional<std::string>("<xmlattr>.class");
488  if (cl_s)
489  {
490  std::string className = *cl_s;
491  const MjcfClass & classE = currentGraph.mapOfClasses.at(className);
492  if (auto site_p = classE.classElement.get_child_optional("site"))
493  goThroughElement(*site_p, currentGraph);
494  }
495 
496  // Site
497  goThroughElement(el, currentGraph);
498  }
499 
501  const GeometryType & type,
502  GeometryModel & geomModel,
503  ::hpp::fcl::MeshLoaderPtr & meshLoader)
504  {
505 #ifdef PINOCCHIO_WITH_HPP_FCL
506  if (!meshLoader)
507  meshLoader = std::make_shared<fcl::MeshLoader>(fcl::MeshLoader());
508 #endif // ifdef PINOCCHIO_WITH_HPP_FCL
509 
510  for (const auto & entry : bodiesList)
511  {
512  const MjcfBody & currentBody = mapOfBodies.at(entry);
513 
514  addLinksToGeomModel(currentBody, *this, geomModel, meshLoader, type);
515  }
516  }
517  } // namespace details
518  } // namespace mjcf
519 } // namespace pinocchio
pinocchio::mjcf::details::retrieveCollisionGeometry
static std::shared_ptr< fcl::CollisionGeometry > retrieveCollisionGeometry(::hpp::fcl::MeshLoaderPtr &, const MjcfGeom &, const MjcfGraph &, std::string &, Eigen::Vector3d &)
Get a fcl::CollisionObject from an mjcf geometry, searching for it in specified package directories.
Definition: mjcf-graph-geom.cpp:128
pinocchio::FrameIndex
Index FrameIndex
Definition: multibody/fwd.hpp:28
pinocchio::mjcf::details::MjcfSite::siteName
std::string siteName
Definition: mjcf-graph.hpp:322
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromEllipsoid
static InertiaTpl FromEllipsoid(const Scalar mass, const Scalar x, const Scalar y, const Scalar z)
Computes the Inertia of an ellipsoid defined by its mass and main semi-axis dimensions (x,...
Definition: spatial/inertia.hpp:384
pinocchio::mjcf::details::MjcfGeom::size
Eigen::VectorXd size
Definition: mjcf-graph.hpp:278
pinocchio::mjcf::details::MjcfClass
Structure to stock all default classes information.
Definition: mjcf-graph.hpp:76
pinocchio::mjcf::details::MjcfGraph::mapOfTextures
TextureMap_t mapOfTextures
Definition: mjcf-graph.hpp:352
append-urdf-model-with-another-model.meshColor
meshColor
Definition: append-urdf-model-with-another-model.py:46
pinocchio::mjcf::details::MjcfGeom::COLLISION
@ COLLISION
Definition: mjcf-graph.hpp:255
pinocchio::mjcf::details::MjcfSite::sitePlacement
SE3 sitePlacement
Definition: mjcf-graph.hpp:320
assimp.h
loader.h
pinocchio::mjcf::details::MjcfMaterial::goThroughElement
void goThroughElement(const ptree &el)
Go through a ptree node to look for material tag related.
Definition: mjcf-graph-geom.cpp:195
pinocchio::mjcf::details::MjcfGeom::findKind
void findKind()
Find the geometry kind.
Definition: mjcf-graph-geom.cpp:292
pinocchio::mjcf::details::MjcfGraph::mapOfClasses
ClassMap_t mapOfClasses
Definition: mjcf-graph.hpp:344
pinocchio::mjcf::details::computeVolume
static double computeVolume(const Eigen::VectorXd &size, const std::string &geomType)
Definition: mjcf-graph-geom.cpp:19
pinocchio::mjcf::details::MjcfGeom::geomKind
TYPE geomKind
Definition: mjcf-graph.hpp:265
pinocchio::mjcf::details::MjcfGeom::group
int group
Definition: mjcf-graph.hpp:271
pinocchio::mjcf::details::MjcfGeom::sizeS
std::string sizeS
Definition: mjcf-graph.hpp:274
y
y
pinocchio::SE3Tpl
Definition: context/casadi.hpp:29
pinocchio::mjcf::details::MjcfGeom::computeSize
void computeSize()
Compute Geometry size based on sizeS and fromtoS.
Definition: mjcf-graph-geom.cpp:303
mjcf-graph.hpp
pinocchio::mjcf::details::MjcfGeom::geomType
std::string geomType
Definition: mjcf-graph.hpp:262
pinocchio::mjcf::details::MjcfGeom::geomPlacement
SE3 geomPlacement
Definition: mjcf-graph.hpp:294
pinocchio::mjcf::details::addLinksToGeomModel
static void addLinksToGeomModel(const MjcfBody &currentBody, const MjcfGraph &currentGraph, GeometryModel &geomModel, ::hpp::fcl::MeshLoaderPtr &meshLoader, const GeometryType &type)
Add all geometries associated with a body.
Definition: mjcf-graph-geom.cpp:144
pinocchio::mjcf::details::MjcfGeom::fromtoS
boost::optional< std::string > fromtoS
Definition: mjcf-graph.hpp:276
pinocchio::mjcf::details::MjcfGeom
Definition: mjcf-graph.hpp:246
pinocchio::mjcf::details::MjcfMaterial::shininess
float shininess
Definition: mjcf-graph.hpp:233
pinocchio::GeometryObject
Definition: multibody/geometry-object.hpp:87
pinocchio::mjcf::details::MjcfGraph::parseGeomTree
void parseGeomTree(const GeometryType &type, GeometryModel &geomModel, ::hpp::fcl::MeshLoaderPtr &meshLoader)
Fill geometry model with all the info taken from the mjcf model file.
Definition: mjcf-graph-geom.cpp:500
pinocchio::mjcf::details::MjcfMaterial
All informations related to material are stored here.
Definition: mjcf-graph.hpp:225
pinocchio::mjcf::details::MjcfGeom::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:249
pinocchio::mjcf::details::isType
bool isType(const MjcfGeom &geom, const GeometryType &type)
Definition: mjcf-graph-geom.cpp:48
pinocchio::mjcf::details::MjcfMaterial::rgba
Eigen::Vector4d rgba
Definition: mjcf-graph.hpp:229
pinocchio::mjcf::details::MjcfGeom::rgba
Eigen::Vector4d rgba
Definition: mjcf-graph.hpp:281
pinocchio::mjcf::details::MjcfMaterial::emission
float emission
Definition: mjcf-graph.hpp:237
pinocchio::mjcf::details::MjcfMaterial::reflectance
float reflectance
Definition: mjcf-graph.hpp:231
pinocchio::mjcf::details::MjcfSite::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:318
height
FCL_REAL height() const
simulation-pendulum.type
type
Definition: simulation-pendulum.py:18
pinocchio::FrameTpl
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Definition: multibody/frame.hpp:55
pinocchio::VISUAL
@ VISUAL
Definition: multibody/geometry-object.hpp:26
pinocchio::SE3Tpl::translation
ConstLinearRef translation() const
Definition: se3-base.hpp:52
pinocchio::mjcf::details::MjcfClass::classElement
ptree classElement
Definition: mjcf-graph.hpp:84
pinocchio::mjcf::details::MjcfBody::geomChildren
std::vector< MjcfGeom > geomChildren
Definition: mjcf-graph.hpp:109
pinocchio::mjcf::details::MjcfSite::goThroughElement
void goThroughElement(const ptree &el, const MjcfGraph &currentGraph)
Definition: mjcf-graph-geom.cpp:445
details
pinocchio::mjcf::details::MjcfMaterial::texture
std::string texture
Definition: mjcf-graph.hpp:239
meshcat-viewer-dae.meshScale
meshScale
Definition: meshcat-viewer-dae.py:30
collision-with-point-clouds.geometry
geometry
Definition: collision-with-point-clouds.py:81
pinocchio::mjcf::details::MjcfTexture::filePath
std::string filePath
Definition: mjcf-graph.hpp:219
mat
mat
pinocchio::SE3Tpl::rotation
ConstAngularRef rotation() const
Definition: se3-base.hpp:48
size
FCL_REAL size() const
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromCapsule
static InertiaTpl FromCapsule(const Scalar mass, const Scalar radius, const Scalar height)
Computes the Inertia of a capsule defined by its mass, radius and length along the Z axis....
Definition: spatial/inertia.hpp:434
x
x
pinocchio::mjcf::details::MjcfMaterial::specular
float specular
Definition: mjcf-graph.hpp:235
pinocchio::mjcf::details::MjcfGraph::bodiesList
VectorOfStrings bodiesList
Definition: mjcf-graph.hpp:363
pinocchio::mjcf::details::MjcfGeom::computeInertia
void computeInertia()
Compute geometry inertia.
Definition: mjcf-graph-geom.cpp:365
pinocchio::mjcf::details::MjcfBody::siteChildren
std::vector< MjcfSite > siteChildren
Definition: mjcf-graph.hpp:111
pinocchio::mjcf::details::MjcfGraph::mapOfBodies
BodyMap_t mapOfBodies
Definition: mjcf-graph.hpp:346
contact-cholesky.frame
frame
Definition: contact-cholesky.py:27
pinocchio::mjcf::details::MjcfGeom::geomName
std::string geomName
Definition: mjcf-graph.hpp:259
anymal-simulation.mass
mass
Definition: anymal-simulation.py:78
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
contact-cholesky.frame_id
frame_id
Definition: contact-cholesky.py:22
pinocchio::mjcf::details::MjcfGraph::mapOfMaterials
MaterialMap_t mapOfMaterials
Definition: mjcf-graph.hpp:348
pinocchio::GeometryModel::addGeometryObject
GeomIndex addGeometryObject(const GeometryObject &object, const ModelTpl< S2, O2, _JointCollectionTpl > &model)
Add a geometry object to a GeometryModel and set its parent joint.
pinocchio::mjcf::details::MjcfGeom::materialName
std::string materialName
Definition: mjcf-graph.hpp:284
pinocchio::mjcf::details::MjcfGeom::meshName
std::string meshName
Definition: mjcf-graph.hpp:286
pinocchio::mjcf::details::MjcfGeom::BOTH
@ BOTH
Definition: mjcf-graph.hpp:256
pinocchio::mjcf::details::MjcfGraph::urdfVisitor
UrdfVisitor & urdfVisitor
Definition: mjcf-graph.hpp:373
pinocchio::mjcf::details::MjcfGraph::convertPosition
SE3 convertPosition(const ptree &el) const
Convert pose of an mjcf element into SE3.
Definition: mjcf-graph.cpp:273
pinocchio::mjcf::details::MjcfBody::bodyName
std::string bodyName
Definition: mjcf-graph.hpp:92
pinocchio::mjcf::details::MjcfGeom::conaffinity
int conaffinity
Definition: mjcf-graph.hpp:269
pinocchio::mjcf::details::MjcfGraph
The graph which contains all information taken from the mjcf file.
Definition: mjcf-graph.hpp:329
pinocchio::GeometryType
GeometryType
Definition: multibody/geometry-object.hpp:24
pinocchio::mjcf::details::MjcfBody
All Bodies informations extracted from mjcf model.
Definition: mjcf-graph.hpp:88
pinocchio::mjcf::details::MjcfGeom::geomInertia
Inertia geomInertia
Definition: mjcf-graph.hpp:296
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromBox
static InertiaTpl FromBox(const Scalar mass, const Scalar x, const Scalar y, const Scalar z)
Computes the Inertia of a box defined by its mass and main dimensions (x,y,z).
Definition: spatial/inertia.hpp:418
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
pinocchio::COLLISION
@ COLLISION
Definition: multibody/geometry-object.hpp:27
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromSphere
static InertiaTpl FromSphere(const Scalar mass, const Scalar radius)
Computes the Inertia of a sphere defined by its mass and its radius.
Definition: spatial/inertia.hpp:369
pinocchio::GeometryObject::CollisionGeometryPtr
std::shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
Definition: multibody/geometry-object.hpp:102
pinocchio::mjcf::details::MjcfMaterial::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:227
pinocchio::mjcf::details::MjcfGeom::goThroughElement
void goThroughElement(const ptree &el, const MjcfGraph &currentGraph)
@bried Go through a geom ptree node, to gather informations
Definition: mjcf-graph-geom.cpp:223
pinocchio::mjcf::details::MjcfBody::childClass
std::string childClass
Definition: mjcf-graph.hpp:99
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromCylinder
static InertiaTpl FromCylinder(const Scalar mass, const Scalar radius, const Scalar length)
Computes the Inertia of a cylinder defined by its mass, radius and length along the Z axis.
Definition: spatial/inertia.hpp:401
pinocchio::mjcf::details::MjcfGeom::massGeom
boost::optional< double > massGeom
Definition: mjcf-graph.hpp:298
meshcat-viewer.overrideMaterial
overrideMaterial
Definition: meshcat-viewer.py:64
hpp::fcl::BVHModelPtr_t
shared_ptr< BVHModelBase > BVHModelPtr_t
radius
FCL_REAL radius
pinocchio::mjcf::details::MjcfTexture
All informations related to a texture are stored here.
Definition: mjcf-graph.hpp:214
pinocchio::mjcf::details::MjcfSite::fill
void fill(const ptree &el, const MjcfBody &currentBody, const MjcfGraph &currentGraph)
Definition: mjcf-graph-geom.cpp:467
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::mjcf::details::MjcfGeom::VISUAL
@ VISUAL
Definition: mjcf-graph.hpp:254
pinocchio::mjcf::details::MjcfGeom::density
double density
Definition: mjcf-graph.hpp:289
pinocchio::mjcf::details::MjcfGeom::contype
int contype
Definition: mjcf-graph.hpp:268


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:39