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 
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 #include <map>
25 
26 namespace pinocchio
27 {
28  namespace mjcf
29  {
30  namespace details
31  {
32  struct MjcfGraph;
33  struct MjcfJoint;
34  struct MjcfGeom;
35  struct MjcfSite;
36 
39  struct PINOCCHIO_PARSERS_DLLAPI MjcfCompiler
40  {
41  public:
42  // Global attribute to use limit that are in the model or not
43  bool autolimits = true;
44 
45  // Attribute to keep or not the full path of files specified in the model
46  bool strippath = false;
47  // Directory where all the meshes are (can be relative or absolute)
48  std::string meshdir;
49  // Directory where all the textures are (can be relative or absolute)
50  std::string texturedir;
51 
52  // Value for angle conversion (Mujoco default - degrees)
53  double angle_converter = boost::math::constants::pi<double>() / 180.0;
54  // Euler Axis to use to convert angles representation to quaternion
55  Eigen::Matrix3d mapEulerAngles;
56 
57  // Value to crop the mass (if mass < boundMass, mass = boundMass)
58  double boundMass = 0;
59  // Value to crop the diagonal of the inertia matrix (if mass < boundMass, mass = boundMass)
60  double boundInertia = 0;
61 
62  // True, false or auto - auto = indeterminate
63  boost::logic::tribool inertiafromgeom = boost::logic::indeterminate;
64 
68  double convertAngle(const double & angle_) const;
69 
73  Eigen::Matrix3d convertEuler(const Eigen::Vector3d & angles) const;
74  };
75 
77  struct MjcfClass
78  {
79  public:
81 
82  // name of the default class
83  std::string className;
84  // Ptree associated with the class name
86  };
87 
89  struct MjcfBody
90  {
91  public:
92  // Name of the body
93  std::string bodyName;
94  // Name of the parent
95  std::string bodyParent;
96  // Name of the default class used by this body (optional)
97  std::string bodyClassName;
98  // Special default class, that is common to all bodies and children if not specified
99  // otherwise
100  std::string childClass;
101 
102  // Position of the body wrt to the previous body
104  // Body inertia
106 
107  // Vector of joints associated with the body
108  std::vector<MjcfJoint> jointChildren;
109  // Vector of geometries associated with the body
110  std::vector<MjcfGeom> geomChildren;
111  // Vector of sites
112  std::vector<MjcfSite> siteChildren;
113  };
114 
116  struct PINOCCHIO_PARSERS_DLLAPI RangeJoint
117  {
118  // Max effort
119  Eigen::VectorXd maxEffort;
120  // Max velocity
121  Eigen::VectorXd maxVel;
122  // Max position
123  Eigen::VectorXd maxConfig;
124  // Min position
125  Eigen::VectorXd minConfig;
126 
127  // Join Stiffness
128  Eigen::VectorXd springStiffness;
129  // joint position or angle in which the joint spring (if any) achieves equilibrium
130  Eigen::VectorXd springReference;
131 
132  // friction applied in this joint
133  Eigen::VectorXd friction;
134  // Damping applied by this joint.
135  Eigen::VectorXd damping;
136 
137  // Armature inertia created by this joint
138  Eigen::VectorXd armature;
139  // Dry friction.
140  double frictionLoss = 0.;
141 
142  RangeJoint() = default;
143  explicit RangeJoint(double v)
144  {
145  const double infty = std::numeric_limits<double>::infinity();
146  maxVel = Eigen::VectorXd::Constant(1, infty);
147  maxEffort = Eigen::VectorXd::Constant(1, infty);
148  minConfig = Eigen::VectorXd::Constant(1, -infty);
149  maxConfig = Eigen::VectorXd::Constant(1, infty);
150  springStiffness = Eigen::VectorXd::Constant(1, v);
151  springReference = Eigen::VectorXd::Constant(1, v);
152  friction = Eigen::VectorXd::Constant(1, 0.);
153  damping = Eigen::VectorXd::Constant(1, 0.);
154  armature = Eigen::VectorXd::Constant(1, 0.);
155  }
156 
161  template<int Nq, int Nv>
162  RangeJoint setDimension() const;
163 
169  template<int Nq, int Nv>
170  RangeJoint concatenate(const RangeJoint & range) const;
171  };
172 
174  struct PINOCCHIO_PARSERS_DLLAPI MjcfJoint
175  {
176  public:
178 
179  // Name of the joint
180  std::string jointName = "free";
181  // Placement of the joint wrt to its body - default Identity
182  SE3 jointPlacement = SE3::Identity();
183 
184  // axis of the joint - default "0 0 1"
185  Eigen::Vector3d axis = Eigen::Vector3d::UnitZ();
186  // Limits that applie to this joint
187  RangeJoint range{1};
188 
189  // type of the joint (hinge, ball, slide, free) - default "hinge"
190  std::string jointType = "hinge";
191 
192  double posRef = 0.; // only possible for hinge and slides
193 
197  void fill(const ptree & el, const MjcfBody & currentBody, const MjcfGraph & currentGraph);
198 
202  void
203  goThroughElement(const ptree & el, bool use_limits, const MjcfCompiler & currentCompiler);
204  };
206  struct MjcfMesh
207  {
208  // Scale of the mesh
209  Eigen::Vector3d scale = Eigen::Vector3d::Constant(1);
210  // Path to the mesh file
211  std::string filePath;
212  };
213 
215  struct MjcfTexture
216  {
217  // [2d, cube, skybox], “cube”
218  std::string textType = "cube";
219  // Path to the texture file
220  std::string filePath;
221  // Size of the grid if needed
222  Eigen::Vector2d gridsize = Eigen::Vector2d::Constant(1);
223  };
224 
226  struct PINOCCHIO_PARSERS_DLLAPI MjcfMaterial
227  {
229  // Color of the material
230  Eigen::Vector4d rgba = Eigen::Vector4d::Constant(1);
231 
232  float reflectance = 0;
233 
234  float shininess = 0.5;
235 
236  float specular = 0.5;
237 
238  float emission = 0;
239  // name of the texture to apply on the material
240  std::string texture;
241 
244  void goThroughElement(const ptree & el);
245  };
246 
247  struct PINOCCHIO_PARSERS_DLLAPI MjcfGeom
248  {
249  public:
251 
252  // Kind of possible geometry
253  enum TYPE
254  {
257  BOTH
258  };
259  // name of the geometry object
260  std::string geomName;
261 
262  // [plane, hfield, sphere, capsule, ellipsoid, cylinder, box, mesh, sdf], “sphere”
263  std::string geomType = "sphere";
264 
265  // Kind of the geometry object
266  TYPE geomKind = BOTH;
267 
268  // Contact filtering and dynamic pair (used here to determine geometry kind)
269  int contype = 1;
270  int conaffinity = 1;
271  // Geometry group (used to determine geometry kind)
272  int group = 0;
273 
274  // String that hold size parameter
275  std::string sizeS;
276  // Optional in case fromto tag is used
277  boost::optional<std::string> fromtoS;
278  // Size parameter
279  Eigen::VectorXd size;
280 
281  // Color of the geometry
282  Eigen::Vector4d rgba = Eigen::Vector4d::Constant(1);
283 
284  // Name of the material applied on the geometry
285  std::string materialName;
286  // Name of the mesh (optional)
287  std::string meshName;
288 
289  // Density for computing the mass
290  double density = 1000;
291  // If mass is only on the outer layer of the geometry
292  bool shellinertia = false;
293 
294  // Geometry Placement in parent body. Center of the frame of geometry is the center of mass.
295  SE3 geomPlacement = SE3::Identity();
296  // Inertia of the geometry obj
297  Inertia geomInertia = Inertia::Identity();
298  // optional mass (if not defined, will use density)
299  boost::optional<double> massGeom;
300 
302  void findKind();
303 
305  void computeSize();
306 
308  void computeInertia();
309 
311  void fill(const ptree & el, const MjcfBody & currentBody, const MjcfGraph & currentGraph);
312 
314  void goThroughElement(const ptree & el, const MjcfGraph & currentGraph);
315  };
316 
317  struct PINOCCHIO_PARSERS_DLLAPI MjcfSite
318  {
320 
321  SE3 sitePlacement = SE3::Identity();
322 
323  std::string siteName;
324 
325  void fill(const ptree & el, const MjcfBody & currentBody, const MjcfGraph & currentGraph);
326  void goThroughElement(const ptree & el, const MjcfGraph & currentGraph);
327  };
328 
329  /*
330  typedef struct mjsEquality_ { // equality specification
331  mjsElement* element; // element type
332  mjString* name; // name
333  mjtEq type; // constraint type
334  double data[mjNEQDATA]; // type-dependent data
335  mjtByte active; // is equality initially active
336  mjString* name1; // name of object 1
337  mjString* name2; // name of object 2
338  mjtNum solref[mjNREF]; // solver reference
339  mjtNum solimp[mjNIMP]; // solver impedance
340  mjString* info; // message appended to errors
341  } mjsEquality;
342  */
343  struct PINOCCHIO_PARSERS_DLLAPI MjcfEquality
344  {
346 
347  // Optional name of the equality constraint
348  std::string name;
349 
350  // Type of the constraint: (connect for now)
351  std::string type;
352 
353  // // Optional class for setting unspecified attributes
354  // std::string class;
355 
356  // active: 'true' or 'false' (default: 'true')
357  // solref and solimp
358 
359  // Name of the first body participating in the constraint
360  std::string body1;
361  // Name of the second body participating in the constraint (optional, default: world)
362  std::string body2;
363 
364  // Coordinates of the 3D anchor point where the two bodies are connected.
365  // Specified relative to the local coordinate frame of the first body.
366  Eigen::Vector3d anchor = Eigen::Vector3d::Zero();
367 
368  // TODO: implement when weld is introduced
369  // This attribute specifies the relative pose (3D position followed by 4D quaternion
370  // orientation) of body2 relative to body1. If the quaternion part (i.e., last 4 components
371  // of the vector) are all zeros, as in the default setting, this attribute is ignored and
372  // the relative pose is the one corresponding to the model reference pose in qpos0. The
373  // unusual default is because all equality constraint types share the same default for their
374  // numeric parameters.
375  // Eigen::VectorXd relativePose = Eigen::VectorXd::Zero(7);
376  };
377 
379  struct PINOCCHIO_PARSERS_DLLAPI MjcfGraph
380  {
381  public:
383  typedef std::vector<std::string> VectorOfStrings;
384  typedef std::unordered_map<std::string, MjcfBody> BodyMap_t;
385  typedef std::unordered_map<std::string, MjcfClass> ClassMap_t;
386  typedef std::unordered_map<std::string, MjcfMaterial> MaterialMap_t;
387  typedef std::unordered_map<std::string, MjcfMesh> MeshMap_t;
388  typedef std::unordered_map<std::string, MjcfTexture> TextureMap_t;
389  typedef std::unordered_map<std::string, Eigen::VectorXd> ConfigMap_t;
390  typedef std::map<std::string, MjcfEquality> EqualityMap_t;
391 
392  // Compiler Info needed to properly parse the rest of file
394  // Map of default classes
396  // Map of bodies
398  // Map of Materials
400  // Map of Meshes
402  // Map of textures
404  // Map of model configurations
406  // Map of equality constraints
408 
409  // reference configuration
410  Eigen::VectorXd referenceConfig;
411 
412  // property tree where xml file is stored
414 
415  // Ordered list of bodies
417 
418  // Name of the model
419  std::string modelName;
420  std::string modelPath;
421 
422  // Urdf Visitor to add joint and body
423  typedef pinocchio::urdf::details::
424  UrdfVisitor<double, 0, ::pinocchio::JointCollectionDefaultTpl>
427 
430  MjcfGraph(UrdfVisitor & urdfVisitor, const std::string & modelPath)
431  : modelPath(modelPath)
432  , urdfVisitor(urdfVisitor)
433  {
434  }
435 
439  SE3 convertPosition(const ptree & el) const;
440 
444  Inertia convertInertiaFromMjcf(const ptree & el) const;
445 
449  void parseDefault(ptree & el, const ptree & parent, const std::string & parentTag);
450 
455  void parseJointAndBody(
456  const ptree & el,
457  const boost::optional<std::string> & childClass,
458  const std::string & parentName = "");
459 
462  void parseCompiler(const ptree & el);
463 
466  void parseTexture(const ptree & el);
467 
470  void parseMaterial(const ptree & el);
471 
474  void parseMesh(const ptree & el);
475 
478  void parseAsset(const ptree & el);
479 
482  void parseKeyFrame(const ptree & el);
483 
486  void parseEquality(const ptree & el);
487 
489  void parseGraph();
490 
493  void parseGraphFromXML(const std::string & xmlStr);
494 
502  template<typename TypeX, typename TypeY, typename TypeZ, typename TypeUnaligned>
503  JointModel createJoint(const Eigen::Vector3d & axis);
504 
509  void
510  addSoloJoint(const MjcfJoint & jointInfo, const MjcfBody & currentBody, SE3 & bodyInJoint);
511 
515  void fillModel(const std::string & nameOfBody);
516 
518  void parseRootTree();
519 
522  void fillReferenceConfig(const MjcfBody & currentBody);
523 
527  void addKeyFrame(const Eigen::VectorXd & keyframe, const std::string & keyName);
528 
533  const Model & model,
535 
540  void parseGeomTree(
541  const GeometryType & type,
542  GeometryModel & geomModel,
543  ::hpp::fcl::MeshLoaderPtr & meshLoader);
544  };
545  namespace internal
546  {
547  inline std::istringstream getConfiguredStringStream(const std::string & str)
548  {
549  std::istringstream posStream(str);
550  posStream.exceptions(std::ios::failbit);
551  return posStream;
552  }
553 
554  template<int N>
555  inline Eigen::Matrix<double, N, 1> getVectorFromStream(const std::string & str)
556  {
557  std::istringstream stream = getConfiguredStringStream(str);
558  Eigen::Matrix<double, N, 1> vector;
559  for (int i = 0; i < N; i++)
560  stream >> vector(i);
561 
562  return vector;
563  }
564 
565  inline Eigen::VectorXd getUnknownSizeVectorFromStream(const std::string & str)
566  {
567  std::istringstream stream = getConfiguredStringStream(str);
568  std::vector<double> vector;
569  double elem;
570  while (!stream.eof())
571  {
572  stream >> elem;
573  vector.push_back(elem);
574  }
575 
576  Eigen::VectorXd returnVector(vector.size());
577  for (std::size_t i = 0; i < vector.size(); i++)
578  returnVector(static_cast<Eigen::Index>(i)) = vector[i];
579 
580  return returnVector;
581  }
582  } // namespace internal
583  } // namespace details
584  } // namespace mjcf
585 } // namespace pinocchio
586 
587 #endif // __pinocchio_parsers_mjcf_graph_hpp__
pinocchio::mjcf::details::MjcfEquality::type
std::string type
Definition: mjcf-graph.hpp:351
pinocchio::InertiaTpl< context::Scalar, context::Options >
common_symbols.type
type
Definition: common_symbols.py:35
pinocchio::mjcf::details::MjcfSite::siteName
std::string siteName
Definition: mjcf-graph.hpp:323
pinocchio::mjcf::details::MjcfCompiler::mapEulerAngles
Eigen::Matrix3d mapEulerAngles
Definition: mjcf-graph.hpp:55
pinocchio::mjcf::details::MjcfGeom::size
Eigen::VectorXd size
Definition: mjcf-graph.hpp:279
pinocchio::mjcf::details::MjcfClass
Structure to stock all default classes information.
Definition: mjcf-graph.hpp:77
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::MjcfGeom::COLLISION
@ COLLISION
Definition: mjcf-graph.hpp:256
pinocchio::mjcf::details::MjcfGraph::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:382
pinocchio::mjcf::details::MjcfTexture::textType
std::string textType
Definition: mjcf-graph.hpp:218
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::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:206
lambdas.parent
parent
Definition: lambdas.py:21
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::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::MjcfGeom::sizeS
std::string sizeS
Definition: mjcf-graph.hpp:275
pinocchio::mjcf::details::MjcfGraph::VectorOfStrings
std::vector< std::string > VectorOfStrings
Definition: mjcf-graph.hpp:383
pinocchio::mjcf::details::RangeJoint::maxVel
Eigen::VectorXd maxVel
Definition: mjcf-graph.hpp:121
pinocchio::SE3Tpl< context::Scalar, context::Options >
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:17
model.hpp
pinocchio::mjcf::details::MjcfTexture::gridsize
Eigen::Vector2d gridsize
Definition: mjcf-graph.hpp:222
pinocchio::mjcf::details::MjcfGeom::fromtoS
boost::optional< std::string > fromtoS
Definition: mjcf-graph.hpp:277
pinocchio::mjcf::details::MjcfGeom
Definition: mjcf-graph.hpp:247
pinocchio::mjcf::details::MjcfEquality::body1
std::string body1
Definition: mjcf-graph.hpp:360
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
pinocchio::mjcf::details::MjcfGraph::ClassMap_t
std::unordered_map< std::string, MjcfClass > ClassMap_t
Definition: mjcf-graph.hpp:385
pinocchio::mjcf::details::MjcfMaterial
All informations related to material are stored here.
Definition: mjcf-graph.hpp:226
pinocchio::mjcf::details::MjcfGeom::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:250
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::MjcfGraph::EqualityMap_t
std::map< std::string, MjcfEquality > EqualityMap_t
Definition: mjcf-graph.hpp:390
pinocchio::mjcf::details::MjcfSite::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:319
pinocchio::sdf::details::parseContactInformation
void parseContactInformation(const SdfGraph &graph, const urdf::details::UrdfVisitorBase &visitor, const Model &model, PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) &contact_models)
Definition: src/parsers/sdf/model.cpp:47
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:405
pinocchio::mjcf::details::MjcfGraph::MjcfGraph
MjcfGraph(UrdfVisitor &urdfVisitor, const std::string &modelPath)
graph constructor
Definition: mjcf-graph.hpp:430
hpp::fcl::MeshLoaderPtr
std::shared_ptr< MeshLoader > MeshLoaderPtr
Definition: meshloader-fwd.hpp:25
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::MjcfMesh::filePath
std::string filePath
Definition: mjcf-graph.hpp:211
pinocchio::mjcf::details::RangeJoint::RangeJoint
RangeJoint(double v)
Definition: mjcf-graph.hpp:143
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::mjcf::details::MjcfMaterial::texture
std::string texture
Definition: mjcf-graph.hpp:240
pinocchio::mjcf::details::RangeJoint::damping
Eigen::VectorXd damping
Definition: mjcf-graph.hpp:135
pinocchio::mjcf::details::MjcfMesh::scale
Eigen::Vector3d scale
Definition: mjcf-graph.hpp:209
pinocchio::RigidConstraintModelTpl
Definition: algorithm/constraints/fwd.hpp:14
pinocchio::mjcf::details::MjcfTexture::filePath
std::string filePath
Definition: mjcf-graph.hpp:220
urdf.hpp
anymal-simulation.N
int N
Definition: anymal-simulation.py:53
pinocchio::mjcf::details::MjcfGraph::MeshMap_t
std::unordered_map< std::string, MjcfMesh > MeshMap_t
Definition: mjcf-graph.hpp:387
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:389
pinocchio::mjcf::details::MjcfGraph::MaterialMap_t
std::unordered_map< std::string, MjcfMaterial > MaterialMap_t
Definition: mjcf-graph.hpp:386
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::mapOfMeshes
MeshMap_t mapOfMeshes
Definition: mjcf-graph.hpp:401
pinocchio::mjcf::details::MjcfGraph::mapOfBodies
BodyMap_t mapOfBodies
Definition: mjcf-graph.hpp:397
axis
axis
pinocchio::mjcf::details::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.cpp:15
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR
#define PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(T)
Definition: container/aligned-vector.hpp:13
pinocchio::mjcf::details::MjcfGeom::geomName
std::string geomName
Definition: mjcf-graph.hpp:260
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::MjcfGraph::UrdfVisitor
pinocchio::urdf::details::UrdfVisitor< double, 0, ::pinocchio::JointCollectionDefaultTpl > UrdfVisitor
Definition: mjcf-graph.hpp:425
pinocchio::mjcf::details::MjcfGeom::materialName
std::string materialName
Definition: mjcf-graph.hpp:285
pinocchio::mjcf::details::MjcfCompiler::texturedir
std::string texturedir
Definition: mjcf-graph.hpp:50
pinocchio::mjcf::details::MjcfGeom::meshName
std::string meshName
Definition: mjcf-graph.hpp:287
pinocchio::mjcf::details::MjcfGraph::urdfVisitor
UrdfVisitor & urdfVisitor
Definition: mjcf-graph.hpp:426
pinocchio::mjcf::details::MjcfGraph::BodyMap_t
std::unordered_map< std::string, MjcfBody > BodyMap_t
Definition: mjcf-graph.hpp:384
fill
fill
pinocchio::mjcf::details::MjcfEquality::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:345
pinocchio::InertiaTpl< context::Scalar, context::Options >::Identity
static InertiaTpl Identity()
Definition: spatial/inertia.hpp:349
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::MjcfGraph::TextureMap_t
std::unordered_map< std::string, MjcfTexture > TextureMap_t
Definition: mjcf-graph.hpp:388
pinocchio::mjcf::details::MjcfGeom::TYPE
TYPE
Definition: mjcf-graph.hpp:253
pinocchio::SE3Tpl::Identity
static SE3Tpl Identity()
Definition: spatial/se3-tpl.hpp:136
pinocchio::mjcf::details::MjcfBody::bodyName
std::string bodyName
Definition: mjcf-graph.hpp:93
pinocchio::mjcf::details::MjcfBody::bodyParent
std::string bodyParent
Definition: mjcf-graph.hpp:95
pinocchio::mjcf::details::MjcfGraph
The graph which contains all information taken from the mjcf file.
Definition: mjcf-graph.hpp:379
pinocchio::mjcf::details::MjcfClass::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:80
pinocchio::mjcf::details::MjcfBody::jointChildren
std::vector< MjcfJoint > jointChildren
Definition: mjcf-graph.hpp:108
pinocchio::GeometryType
GeometryType
Definition: multibody/geometry-object.hpp:24
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
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: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::mjcf::details::MjcfMaterial::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.hpp:228
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::mjcf::details::MjcfBody::childClass
std::string childClass
Definition: mjcf-graph.hpp:100
pinocchio::mjcf::details::internal::getVectorFromStream
Eigen::Matrix< double, N, 1 > getVectorFromStream(const std::string &str)
Definition: mjcf-graph.hpp:555
pinocchio::mjcf::details::MjcfGeom::massGeom
boost::optional< double > massGeom
Definition: mjcf-graph.hpp:299
pinocchio::mjcf::details::internal::getUnknownSizeVectorFromStream
Eigen::VectorXd getUnknownSizeVectorFromStream(const std::string &str)
Definition: mjcf-graph.hpp:565
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
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::mjcf::details::MjcfGeom::VISUAL
@ VISUAL
Definition: mjcf-graph.hpp:255


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