mjcf-graph.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2024 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_parsers_mjcf_graph_hpp__
6 #define __pinocchio_parsers_mjcf_graph_hpp__
7 
11 
12 #include <boost/property_tree/xml_parser.hpp>
13 #include <boost/property_tree/ptree.hpp>
14 #include <boost/foreach.hpp>
15 #include <boost/math/constants/constants.hpp>
16 #include <boost/filesystem.hpp>
17 #include <boost/logic/tribool.hpp>
18 #include <boost/lexical_cast.hpp>
19 
20 #include <sstream>
21 #include <limits>
22 #include <iostream>
23 #include <unordered_map>
24 
25 namespace pinocchio
26 {
27  namespace mjcf
28  {
29  namespace details
30  {
31  struct MjcfGraph;
32  struct MjcfJoint;
33  struct MjcfGeom;
34  struct MjcfSite;
35 
38  struct PINOCCHIO_PARSERS_DLLAPI MjcfCompiler
39  {
40  public:
41  // Global attribute to use limit that are in the model or not
42  bool autolimits = true;
43 
44  // Attribute to keep or not the full path of files specified in the model
45  bool strippath = false;
46  // Directory where all the meshes are (can be relative or absolute)
47  std::string meshdir;
48  // Directory where all the textures are (can be relative or absolute)
49  std::string texturedir;
50 
51  // Value for angle conversion (Mujoco default - degrees)
52  double angle_converter = boost::math::constants::pi<double>() / 180.0;
53  // Euler Axis to use to convert angles representation to quaternion
54  Eigen::Matrix3d mapEulerAngles;
55 
56  // Value to crop the mass (if mass < boundMass, mass = boundMass)
57  double boundMass = 0;
58  // Value to crop the diagonal of the inertia matrix (if mass < boundMass, mass = boundMass)
59  double boundInertia = 0;
60 
61  // True, false or auto - auto = indeterminate
62  boost::logic::tribool inertiafromgeom = boost::logic::indeterminate;
63 
67  double convertAngle(const double & angle_) const;
68 
72  Eigen::Matrix3d convertEuler(const Eigen::Vector3d & angles) const;
73  };
74 
76  struct MjcfClass
77  {
78  public:
80 
81  // name of the default class
82  std::string className;
83  // Ptree associated with the class name
85  };
86 
88  struct MjcfBody
89  {
90  public:
91  // Name of the body
92  std::string bodyName;
93  // Name of the parent
94  std::string bodyParent;
95  // Name of the default class used by this body (optional)
96  std::string bodyClassName;
97  // Special default class, that is common to all bodies and children if not specified
98  // otherwise
99  std::string childClass;
100 
101  // Position of the body wrt to the previous body
103  // Body inertia
105 
106  // Vector of joints associated with the body
107  std::vector<MjcfJoint> jointChildren;
108  // Vector of geometries associated with the body
109  std::vector<MjcfGeom> geomChildren;
110  // Vector of sites
111  std::vector<MjcfSite> siteChildren;
112  };
113 
115  struct PINOCCHIO_PARSERS_DLLAPI RangeJoint
116  {
117  // Max effort
118  Eigen::VectorXd maxEffort;
119  // Max velocity
120  Eigen::VectorXd maxVel;
121  // Max position
122  Eigen::VectorXd maxConfig;
123  // Min position
124  Eigen::VectorXd minConfig;
125 
126  // Join Stiffness
127  Eigen::VectorXd springStiffness;
128  // joint position or angle in which the joint spring (if any) achieves equilibrium
129  Eigen::VectorXd springReference;
130 
131  // friction applied in this joint
132  Eigen::VectorXd friction;
133  // Damping applied by this joint.
134  Eigen::VectorXd damping;
135 
136  // Armature inertia created by this joint
137  double armature = 0.;
138  // Dry friction.
139  double frictionLoss = 0.;
140 
141  RangeJoint() = default;
142  explicit RangeJoint(double v)
143  {
144  const double infty = std::numeric_limits<double>::infinity();
145  maxVel = Eigen::VectorXd::Constant(1, infty);
146  maxEffort = Eigen::VectorXd::Constant(1, infty);
147  minConfig = Eigen::VectorXd::Constant(1, -infty);
148  maxConfig = Eigen::VectorXd::Constant(1, infty);
149  springStiffness = Eigen::VectorXd::Constant(1, v);
150  springReference = Eigen::VectorXd::Constant(1, v);
151  ;
152  friction = Eigen::VectorXd::Constant(1, 0.);
153  damping = Eigen::VectorXd::Constant(1, 0.);
154  }
155 
160  template<int Nq, int Nv>
161  RangeJoint setDimension() const;
162 
168  template<int Nq, int Nv>
169  RangeJoint concatenate(const RangeJoint & range) const;
170  };
171 
173  struct PINOCCHIO_PARSERS_DLLAPI MjcfJoint
174  {
175  public:
177 
178  // Name of the joint
179  std::string jointName = "free";
180  // Placement of the joint wrt to its body - default Identity
181  SE3 jointPlacement = SE3::Identity();
182 
183  // axis of the joint - default "0 0 1"
184  Eigen::Vector3d axis = Eigen::Vector3d::UnitZ();
185  // Limits that applie to this joint
186  RangeJoint range{1};
187 
188  // type of the joint (hinge, ball, slide, free) - default "hinge"
189  std::string jointType = "hinge";
190 
191  double posRef = 0.; // only possible for hinge and slides
192 
196  void fill(const ptree & el, const MjcfBody & currentBody, const MjcfGraph & currentGraph);
197 
201  void
202  goThroughElement(const ptree & el, bool use_limits, const MjcfCompiler & currentCompiler);
203  };
205  struct MjcfMesh
206  {
207  // Scale of the mesh
208  Eigen::Vector3d scale = Eigen::Vector3d::Constant(1);
209  // Path to the mesh file
210  std::string filePath;
211  };
212 
214  struct MjcfTexture
215  {
216  // [2d, cube, skybox], “cube”
217  std::string textType = "cube";
218  // Path to the texture file
219  std::string filePath;
220  // Size of the grid if needed
221  Eigen::Vector2d gridsize = Eigen::Vector2d::Constant(1);
222  };
223 
225  struct PINOCCHIO_PARSERS_DLLAPI MjcfMaterial
226  {
228  // Color of the material
229  Eigen::Vector4d rgba = Eigen::Vector4d::Constant(1);
230 
231  float reflectance = 0;
232 
233  float shininess = 0.5;
234 
235  float specular = 0.5;
236 
237  float emission = 0;
238  // name of the texture to apply on the material
239  std::string texture;
240 
243  void goThroughElement(const ptree & el);
244  };
245 
246  struct PINOCCHIO_PARSERS_DLLAPI MjcfGeom
247  {
248  public:
250 
251  // Kind of possible geometry
252  enum TYPE
253  {
256  BOTH
257  };
258  // name of the geometry object
259  std::string geomName;
260 
261  // [plane, hfield, sphere, capsule, ellipsoid, cylinder, box, mesh, sdf], “sphere”
262  std::string geomType = "sphere";
263 
264  // Kind of the geometry object
265  TYPE geomKind = BOTH;
266 
267  // Contact filtering and dynamic pair (used here to determine geometry kind)
268  int contype = 1;
269  int conaffinity = 1;
270  // Geometry group (used to determine geometry kind)
271  int group = 0;
272 
273  // String that hold size parameter
274  std::string sizeS;
275  // Optional in case fromto tag is used
276  boost::optional<std::string> fromtoS;
277  // Size parameter
278  Eigen::VectorXd size;
279 
280  // Color of the geometry
281  Eigen::Vector4d rgba = Eigen::Vector4d::Constant(1);
282 
283  // Name of the material applied on the geometry
284  std::string materialName;
285  // Name of the mesh (optional)
286  std::string meshName;
287 
288  // Density for computing the mass
289  double density = 1000;
290  // If mass is only on the outer layer of the geometry
291  bool shellinertia = false;
292 
293  // Geometry Placement in parent body. Center of the frame of geometry is the center of mass.
294  SE3 geomPlacement = SE3::Identity();
295  // Inertia of the geometry obj
296  Inertia geomInertia = Inertia::Identity();
297  // optional mass (if not defined, will use density)
298  boost::optional<double> massGeom;
299 
301  void findKind();
302 
304  void computeSize();
305 
307  void computeInertia();
308 
310  void fill(const ptree & el, const MjcfBody & currentBody, const MjcfGraph & currentGraph);
311 
313  void goThroughElement(const ptree & el, const MjcfGraph & currentGraph);
314  };
315 
316  struct PINOCCHIO_PARSERS_DLLAPI MjcfSite
317  {
319 
320  SE3 sitePlacement = SE3::Identity();
321 
322  std::string siteName;
323 
324  void fill(const ptree & el, const MjcfBody & currentBody, const MjcfGraph & currentGraph);
325  void goThroughElement(const ptree & el, const MjcfGraph & currentGraph);
326  };
327 
329  struct PINOCCHIO_PARSERS_DLLAPI MjcfGraph
330  {
331  public:
333  typedef std::vector<std::string> VectorOfStrings;
334  typedef std::unordered_map<std::string, MjcfBody> BodyMap_t;
335  typedef std::unordered_map<std::string, MjcfClass> ClassMap_t;
336  typedef std::unordered_map<std::string, MjcfMaterial> MaterialMap_t;
337  typedef std::unordered_map<std::string, MjcfMesh> MeshMap_t;
338  typedef std::unordered_map<std::string, MjcfTexture> TextureMap_t;
339  typedef std::unordered_map<std::string, Eigen::VectorXd> ConfigMap_t;
340 
341  // Compiler Info needed to properly parse the rest of file
343  // Map of default classes
345  // Map of bodies
347  // Map of Materials
349  // Map of Meshes
351  // Map of textures
353  // Map of model configurations
355 
356  // reference configuration
357  Eigen::VectorXd referenceConfig;
358 
359  // property tree where xml file is stored
361 
362  // Ordered list of bodies
364 
365  // Name of the model
366  std::string modelName;
367  std::string modelPath;
368 
369  // Urdf Visitor to add joint and body
370  typedef pinocchio::urdf::details::
371  UrdfVisitor<double, 0, ::pinocchio::JointCollectionDefaultTpl>
374 
377  MjcfGraph(UrdfVisitor & urdfVisitor, const std::string & modelPath)
378  : modelPath(modelPath)
379  , urdfVisitor(urdfVisitor)
380  {
381  }
382 
386  SE3 convertPosition(const ptree & el) const;
387 
391  Inertia convertInertiaFromMjcf(const ptree & el) const;
392 
396  void parseDefault(ptree & el, const ptree & parent);
397 
402  void parseJointAndBody(
403  const ptree & el,
404  const boost::optional<std::string> & childClass,
405  const std::string & parentName = "");
406 
409  void parseCompiler(const ptree & el);
410 
413  void parseTexture(const ptree & el);
414 
417  void parseMaterial(const ptree & el);
418 
421  void parseMesh(const ptree & el);
422 
425  void parseAsset(const ptree & el);
426 
429  void parseKeyFrame(const ptree & el);
430 
432  void parseGraph();
433 
436  void parseGraphFromXML(const std::string & xmlStr);
437 
445  template<typename TypeX, typename TypeY, typename TypeZ, typename TypeUnaligned>
446  JointModel createJoint(const Eigen::Vector3d & axis);
447 
452  void
453  addSoloJoint(const MjcfJoint & jointInfo, const MjcfBody & currentBody, SE3 & bodyInJoint);
454 
458  void fillModel(const std::string & nameOfBody);
459 
461  void parseRootTree();
462 
465  void fillReferenceConfig(const MjcfBody & currentBody);
466 
470  void addKeyFrame(const Eigen::VectorXd & keyframe, const std::string & keyName);
471 
476  void parseGeomTree(
477  const GeometryType & type,
478  GeometryModel & geomModel,
479  ::hpp::fcl::MeshLoaderPtr & meshLoader);
480  };
481  namespace internal
482  {
483  inline std::istringstream getConfiguredStringStream(const std::string & str)
484  {
485  std::istringstream posStream(str);
486  posStream.exceptions(std::ios::failbit);
487  return posStream;
488  }
489 
490  template<int N>
491  inline Eigen::Matrix<double, N, 1> getVectorFromStream(const std::string & str)
492  {
493  std::istringstream stream = getConfiguredStringStream(str);
494  Eigen::Matrix<double, N, 1> vector;
495  for (int i = 0; i < N; i++)
496  stream >> vector(i);
497 
498  return vector;
499  }
500 
501  inline Eigen::VectorXd getUnknownSizeVectorFromStream(const std::string & str)
502  {
503  std::istringstream stream = getConfiguredStringStream(str);
504  std::vector<double> vector;
505  double elem;
506  while (!stream.eof())
507  {
508  stream >> elem;
509  vector.push_back(elem);
510  }
511 
512  Eigen::VectorXd returnVector(vector.size());
513  for (std::size_t i = 0; i < vector.size(); i++)
514  returnVector(static_cast<Eigen::Index>(i)) = vector[i];
515 
516  return returnVector;
517  }
518  } // namespace internal
519  } // namespace details
520  } // namespace mjcf
521 } // namespace pinocchio
522 
523 #endif // __pinocchio_parsers_mjcf_graph_hpp__
pinocchio::InertiaTpl< context::Scalar, context::Options >
pinocchio::mjcf::details::MjcfSite::siteName
std::string siteName
Definition: mjcf-graph.hpp:322
pinocchio::mjcf::details::MjcfCompiler::mapEulerAngles
Eigen::Matrix3d mapEulerAngles
Definition: mjcf-graph.hpp:54
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
pinocchio::mjcf::details::MjcfCompiler
Informations that are stocked in the XML tag compile.
Definition: mjcf-graph.hpp:38
pinocchio::mjcf::details::MjcfGeom::COLLISION
@ COLLISION
Definition: mjcf-graph.hpp:255
pinocchio::mjcf::details::MjcfGraph::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:332
pinocchio::mjcf::details::MjcfTexture::textType
std::string textType
Definition: mjcf-graph.hpp:217
pinocchio::mjcf::details::MjcfBody::bodyInertia
Inertia bodyInertia
Definition: mjcf-graph.hpp:104
pinocchio::mjcf::details::MjcfGraph::referenceConfig
Eigen::VectorXd referenceConfig
Definition: mjcf-graph.hpp:357
pinocchio::sdf::details::parseRootTree
void parseRootTree(SdfGraph &graph, const std::string &rootLinkName)
Definition: src/parsers/sdf/model.cpp:69
pinocchio::mjcf::details::MjcfMesh
All informations related to a mesh are stored here.
Definition: mjcf-graph.hpp:205
lambdas.parent
parent
Definition: lambdas.py:20
pinocchio::mjcf::details::MjcfGraph::mapOfClasses
ClassMap_t mapOfClasses
Definition: mjcf-graph.hpp:344
pinocchio::mjcf::details::RangeJoint::maxConfig
Eigen::VectorXd maxConfig
Definition: mjcf-graph.hpp:122
pinocchio::mjcf::details::RangeJoint
All joint limits.
Definition: mjcf-graph.hpp:115
pinocchio::mjcf::details::MjcfGeom::sizeS
std::string sizeS
Definition: mjcf-graph.hpp:274
pinocchio::mjcf::details::MjcfGraph::VectorOfStrings
std::vector< std::string > VectorOfStrings
Definition: mjcf-graph.hpp:333
pinocchio::mjcf::details::RangeJoint::maxVel
Eigen::VectorXd maxVel
Definition: mjcf-graph.hpp:120
pinocchio::SE3Tpl< context::Scalar, context::Options >
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:20
model.hpp
pinocchio::mjcf::details::MjcfTexture::gridsize
Eigen::Vector2d gridsize
Definition: mjcf-graph.hpp:221
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::MjcfJoint
All joint information parsed from the mjcf model.
Definition: mjcf-graph.hpp:173
pinocchio::mjcf::details::RangeJoint::minConfig
Eigen::VectorXd minConfig
Definition: mjcf-graph.hpp:124
pinocchio::mjcf::details::MjcfGraph::ClassMap_t
std::unordered_map< std::string, MjcfClass > ClassMap_t
Definition: mjcf-graph.hpp:335
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::MjcfClass::className
std::string className
Definition: mjcf-graph.hpp:82
pinocchio::mjcf::details::MjcfGraph::modelName
std::string modelName
Definition: mjcf-graph.hpp:366
pinocchio::mjcf::details::RangeJoint::friction
Eigen::VectorXd friction
Definition: mjcf-graph.hpp:132
pinocchio::mjcf::details::MjcfSite::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:318
simulation-pendulum.type
type
Definition: simulation-pendulum.py:18
pinocchio::Index
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
Definition: multibody/fwd.hpp:22
pinocchio::mjcf::details::MjcfGraph::mapOfConfigs
ConfigMap_t mapOfConfigs
Definition: mjcf-graph.hpp:354
pinocchio::mjcf::details::MjcfGraph::MjcfGraph
MjcfGraph(UrdfVisitor &urdfVisitor, const std::string &modelPath)
graph constructor
Definition: mjcf-graph.hpp:377
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::MjcfMesh::filePath
std::string filePath
Definition: mjcf-graph.hpp:210
pinocchio::mjcf::details::RangeJoint::RangeJoint
RangeJoint(double v)
Definition: mjcf-graph.hpp:142
pinocchio::mjcf::details::RangeJoint::springReference
Eigen::VectorXd springReference
Definition: mjcf-graph.hpp:129
details
pinocchio::mjcf::details::MjcfJoint::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:176
pinocchio::mjcf::details::MjcfMaterial::texture
std::string texture
Definition: mjcf-graph.hpp:239
pinocchio::mjcf::details::RangeJoint::damping
Eigen::VectorXd damping
Definition: mjcf-graph.hpp:134
pinocchio::mjcf::details::MjcfMesh::scale
Eigen::Vector3d scale
Definition: mjcf-graph.hpp:208
pinocchio::mjcf::details::MjcfTexture::filePath
std::string filePath
Definition: mjcf-graph.hpp:219
urdf.hpp
anymal-simulation.N
int N
Definition: anymal-simulation.py:69
pinocchio::mjcf::details::MjcfGraph::MeshMap_t
std::unordered_map< std::string, MjcfMesh > MeshMap_t
Definition: mjcf-graph.hpp:337
pinocchio::JointModelTpl
Definition: multibody/joint/fwd.hpp:155
pinocchio::mjcf::details::MjcfGraph::ConfigMap_t
std::unordered_map< std::string, Eigen::VectorXd > ConfigMap_t
Definition: mjcf-graph.hpp:339
pinocchio::mjcf::details::MjcfGraph::MaterialMap_t
std::unordered_map< std::string, MjcfMaterial > MaterialMap_t
Definition: mjcf-graph.hpp:336
pinocchio::mjcf::details::MjcfGraph::bodiesList
VectorOfStrings bodiesList
Definition: mjcf-graph.hpp:363
pinocchio::mjcf::details::RangeJoint::springStiffness
Eigen::VectorXd springStiffness
Definition: mjcf-graph.hpp:127
pinocchio::mjcf::details::MjcfBody::siteChildren
std::vector< MjcfSite > siteChildren
Definition: mjcf-graph.hpp:111
pinocchio::mjcf::details::MjcfGraph::mapOfMeshes
MeshMap_t mapOfMeshes
Definition: mjcf-graph.hpp:350
pinocchio::mjcf::details::MjcfGraph::mapOfBodies
BodyMap_t mapOfBodies
Definition: mjcf-graph.hpp:346
axis
axis
pinocchio::mjcf::details::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.cpp:13
pinocchio::mjcf::details::MjcfGeom::geomName
std::string geomName
Definition: mjcf-graph.hpp:259
pinocchio::mjcf::details::MjcfBody::bodyClassName
std::string bodyClassName
Definition: mjcf-graph.hpp:96
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
pinocchio::mjcf::details::MjcfGraph::mapOfMaterials
MaterialMap_t mapOfMaterials
Definition: mjcf-graph.hpp:348
pinocchio::mjcf::details::MjcfCompiler::meshdir
std::string meshdir
Definition: mjcf-graph.hpp:47
pinocchio::mjcf::details::MjcfGraph::UrdfVisitor
pinocchio::urdf::details::UrdfVisitor< double, 0, ::pinocchio::JointCollectionDefaultTpl > UrdfVisitor
Definition: mjcf-graph.hpp:372
pinocchio::mjcf::details::MjcfGeom::materialName
std::string materialName
Definition: mjcf-graph.hpp:284
pinocchio::mjcf::details::MjcfCompiler::texturedir
std::string texturedir
Definition: mjcf-graph.hpp:49
pinocchio::mjcf::details::MjcfGeom::meshName
std::string meshName
Definition: mjcf-graph.hpp:286
pinocchio::mjcf::details::MjcfGraph::urdfVisitor
UrdfVisitor & urdfVisitor
Definition: mjcf-graph.hpp:373
pinocchio::mjcf::details::MjcfGraph::BodyMap_t
std::unordered_map< std::string, MjcfBody > BodyMap_t
Definition: mjcf-graph.hpp:334
fill
fill
pinocchio::InertiaTpl< context::Scalar, context::Options >::Identity
static InertiaTpl Identity()
Definition: spatial/inertia.hpp:344
pinocchio::mjcf::details::MjcfGraph::compilerInfo
MjcfCompiler compilerInfo
Definition: mjcf-graph.hpp:342
pinocchio::mjcf::details::MjcfGraph::pt
ptree pt
Definition: mjcf-graph.hpp:360
pinocchio::mjcf::details::MjcfGraph::TextureMap_t
std::unordered_map< std::string, MjcfTexture > TextureMap_t
Definition: mjcf-graph.hpp:338
pinocchio::mjcf::details::MjcfGeom::TYPE
TYPE
Definition: mjcf-graph.hpp:252
pinocchio::SE3Tpl< context::Scalar, context::Options >::Identity
static SE3Tpl Identity()
Definition: spatial/se3-tpl.hpp:136
pinocchio::mjcf::details::MjcfBody::bodyName
std::string bodyName
Definition: mjcf-graph.hpp:92
pinocchio::mjcf::details::MjcfBody::bodyParent
std::string bodyParent
Definition: mjcf-graph.hpp:94
pinocchio::mjcf::details::MjcfGraph
The graph which contains all information taken from the mjcf file.
Definition: mjcf-graph.hpp:329
pinocchio::mjcf::details::MjcfClass::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:79
pinocchio::mjcf::details::MjcfBody::jointChildren
std::vector< MjcfJoint > jointChildren
Definition: mjcf-graph.hpp:107
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
joints.hpp
str
str
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
pinocchio::mjcf::details::internal::getConfiguredStringStream
std::istringstream getConfiguredStringStream(const std::string &str)
Definition: mjcf-graph.hpp:483
pinocchio::mjcf::details::MjcfSite
Definition: mjcf-graph.hpp:316
pinocchio::mjcf::details::MjcfBody::bodyPlacement
SE3 bodyPlacement
Definition: mjcf-graph.hpp:102
pinocchio::mjcf::details::MjcfMaterial::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:227
pinocchio::mjcf::details::MjcfBody::childClass
std::string childClass
Definition: mjcf-graph.hpp:99
pinocchio::mjcf::details::internal::getVectorFromStream
Eigen::Matrix< double, N, 1 > getVectorFromStream(const std::string &str)
Definition: mjcf-graph.hpp:491
pinocchio::mjcf::details::MjcfGeom::massGeom
boost::optional< double > massGeom
Definition: mjcf-graph.hpp:298
pinocchio::mjcf::details::internal::getUnknownSizeVectorFromStream
Eigen::VectorXd getUnknownSizeVectorFromStream(const std::string &str)
Definition: mjcf-graph.hpp:501
pinocchio::mjcf::details::RangeJoint::maxEffort
Eigen::VectorXd maxEffort
Definition: mjcf-graph.hpp:118
pinocchio::mjcf::details::MjcfTexture
All informations related to a texture are stored here.
Definition: mjcf-graph.hpp:214
pinocchio::mjcf::details::MjcfGraph::modelPath
std::string modelPath
Definition: mjcf-graph.hpp:367
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::mjcf::details::MjcfGeom::VISUAL
@ VISUAL
Definition: mjcf-graph.hpp:254


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