Public Types | Public Member Functions | Public Attributes | List of all members
pinocchio::mjcf::details::MjcfGraph Struct Reference

The graph which contains all information taken from the mjcf file. More...

#include <mjcf-graph.hpp>

Public Types

typedef std::unordered_map< std::string, MjcfBodyBodyMap_t
 
typedef std::unordered_map< std::string, MjcfClassClassMap_t
 
typedef std::unordered_map< std::string, Eigen::VectorXd > ConfigMap_t
 
typedef std::unordered_map< std::string, MjcfMaterialMaterialMap_t
 
typedef std::unordered_map< std::string, MjcfMeshMeshMap_t
 
typedef boost::property_tree::ptree ptree
 
typedef std::unordered_map< std::string, MjcfTextureTextureMap_t
 
typedef pinocchio::urdf::details::UrdfVisitor< double, 0, ::pinocchio::JointCollectionDefaultTplUrdfVisitor
 
typedef std::vector< std::string > VectorOfStrings
 

Public Member Functions

void addKeyFrame (const Eigen::VectorXd &keyframe, const std::string &keyName)
 Add a keyframe to the model (ie reference configuration) More...
 
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. More...
 
Inertia convertInertiaFromMjcf (const ptree &el) const
 Convert Inertia of an mjcf element into Inertia model of pinocchio. More...
 
SE3 convertPosition (const ptree &el) const
 Convert pose of an mjcf element into SE3. More...
 
template<typename TypeX , typename TypeY , typename TypeZ , typename TypeUnaligned >
JointModel createJoint (const Eigen::Vector3d &axis)
 Create a joint to add to the joint composite if needed. More...
 
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. More...
 
void fillReferenceConfig (const MjcfBody &currentBody)
 Fill reference configuration for a body and all it's associated dof. More...
 
 MjcfGraph (UrdfVisitor &urdfVisitor, const std::string &modelPath)
 graph constructor More...
 
void parseAsset (const ptree &el)
 Parse all the info from the meta tag asset (mesh, material, texture) More...
 
void parseCompiler (const ptree &el)
 Parse all the info from the compile node into compilerInfo. More...
 
void parseDefault (ptree &el, const ptree &parent)
 Go through the default part of the file and get all the class name. Fill the mapOfDefault for later use. More...
 
void parseGeomTree (const GeometryType &type, GeometryModel &geomModel, ::hpp::fcl::MeshLoaderPtr &meshLoader)
 Fill geometry model with all the info taken from the mjcf model file. More...
 
void parseGraph ()
 parse the mjcf file into a graph More...
 
void parseGraphFromXML (const std::string &xmlStr)
 parse the mjcf file into a graph More...
 
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. More...
 
void parseKeyFrame (const ptree &el)
 Parse all the info from the meta tag keyframe. More...
 
void parseMaterial (const ptree &el)
 Parse all the info from a material node. More...
 
void parseMesh (const ptree &el)
 Parse all the info from a mesh node. More...
 
void parseRootTree ()
 Fill the pinocchio model with all the infos from the graph. More...
 
void parseTexture (const ptree &el)
 Parse all the info from a texture node. More...
 

Public Attributes

VectorOfStrings bodiesList
 
MjcfCompiler compilerInfo
 
BodyMap_t mapOfBodies
 
ClassMap_t mapOfClasses
 
ConfigMap_t mapOfConfigs
 
MaterialMap_t mapOfMaterials
 
MeshMap_t mapOfMeshes
 
TextureMap_t mapOfTextures
 
std::string modelName
 
std::string modelPath
 
ptree pt
 
Eigen::VectorXd referenceConfig
 
UrdfVisitorurdfVisitor
 

Detailed Description

The graph which contains all information taken from the mjcf file.

Definition at line 329 of file mjcf-graph.hpp.

Member Typedef Documentation

◆ BodyMap_t

typedef std::unordered_map<std::string, MjcfBody> pinocchio::mjcf::details::MjcfGraph::BodyMap_t

Definition at line 334 of file mjcf-graph.hpp.

◆ ClassMap_t

typedef std::unordered_map<std::string, MjcfClass> pinocchio::mjcf::details::MjcfGraph::ClassMap_t

Definition at line 335 of file mjcf-graph.hpp.

◆ ConfigMap_t

typedef std::unordered_map<std::string, Eigen::VectorXd> pinocchio::mjcf::details::MjcfGraph::ConfigMap_t

Definition at line 339 of file mjcf-graph.hpp.

◆ MaterialMap_t

typedef std::unordered_map<std::string, MjcfMaterial> pinocchio::mjcf::details::MjcfGraph::MaterialMap_t

Definition at line 336 of file mjcf-graph.hpp.

◆ MeshMap_t

typedef std::unordered_map<std::string, MjcfMesh> pinocchio::mjcf::details::MjcfGraph::MeshMap_t

Definition at line 337 of file mjcf-graph.hpp.

◆ ptree

typedef boost::property_tree::ptree pinocchio::mjcf::details::MjcfGraph::ptree

Definition at line 332 of file mjcf-graph.hpp.

◆ TextureMap_t

typedef std::unordered_map<std::string, MjcfTexture> pinocchio::mjcf::details::MjcfGraph::TextureMap_t

Definition at line 338 of file mjcf-graph.hpp.

◆ UrdfVisitor

Definition at line 372 of file mjcf-graph.hpp.

◆ VectorOfStrings

typedef std::vector<std::string> pinocchio::mjcf::details::MjcfGraph::VectorOfStrings

Definition at line 333 of file mjcf-graph.hpp.

Constructor & Destructor Documentation

◆ MjcfGraph()

pinocchio::mjcf::details::MjcfGraph::MjcfGraph ( UrdfVisitor urdfVisitor,
const std::string &  modelPath 
)
inline

graph constructor

Parameters
urdfVisitor

Definition at line 377 of file mjcf-graph.hpp.

Member Function Documentation

◆ addKeyFrame()

void pinocchio::mjcf::details::MjcfGraph::addKeyFrame ( const Eigen::VectorXd &  keyframe,
const std::string &  keyName 
)

Add a keyframe to the model (ie reference configuration)

Parameters
keyframeKeyframe to add
keyNameName of the keyframe

Definition at line 965 of file mjcf-graph.cpp.

◆ addSoloJoint()

void pinocchio::mjcf::details::MjcfGraph::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.

Parameters
jointInfoThe joint to add to the tree
currentBodyThe body associated with the joint
bodyInJointPosition of the body wrt to its joint

Definition at line 783 of file mjcf-graph.cpp.

◆ convertInertiaFromMjcf()

Inertia pinocchio::mjcf::details::MjcfGraph::convertInertiaFromMjcf ( const ptree el) const

Convert Inertia of an mjcf element into Inertia model of pinocchio.

Parameters
elptree element with all the inertial information
Returns
Inertia element in pinocchio

Definition at line 344 of file mjcf-graph.cpp.

◆ convertPosition()

SE3 pinocchio::mjcf::details::MjcfGraph::convertPosition ( const ptree el) const

Convert pose of an mjcf element into SE3.

Parameters
elptree element with all the pose element
Returns
pose in SE3

Definition at line 273 of file mjcf-graph.cpp.

◆ createJoint()

template<typename TypeX , typename TypeY , typename TypeZ , typename TypeUnaligned >
JointModel pinocchio::mjcf::details::MjcfGraph::createJoint ( const Eigen::Vector3d &  axis)

Create a joint to add to the joint composite if needed.

Template Parameters
TypeXjoint with axis X
TypeYjoint with axis Y
TypeZjoint with axis Z
TypeUnalignedjoint with axis unaligned
Parameters
axisaxis of the joint
Returns
one of the joint with the right axis

Definition at line 771 of file mjcf-graph.cpp.

◆ fillModel()

void pinocchio::mjcf::details::MjcfGraph::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.

Parameters
nameOfBodyName of the body to add

Definition at line 832 of file mjcf-graph.cpp.

◆ fillReferenceConfig()

void pinocchio::mjcf::details::MjcfGraph::fillReferenceConfig ( const MjcfBody currentBody)

Fill reference configuration for a body and all it's associated dof.

Parameters
currentBodybody to check

Definition at line 943 of file mjcf-graph.cpp.

◆ parseAsset()

void pinocchio::mjcf::details::MjcfGraph::parseAsset ( const ptree el)

Parse all the info from the meta tag asset (mesh, material, texture)

Parameters
elptree texture node

Definition at line 569 of file mjcf-graph.cpp.

◆ parseCompiler()

void pinocchio::mjcf::details::MjcfGraph::parseCompiler ( const ptree el)

Parse all the info from the compile node into compilerInfo.

Parameters
elptree compile node

Definition at line 611 of file mjcf-graph.cpp.

◆ parseDefault()

void pinocchio::mjcf::details::MjcfGraph::parseDefault ( ptree el,
const ptree parent 
)

Go through the default part of the file and get all the class name. Fill the mapOfDefault for later use.

Parameters
elptree element. Root of the default

Definition at line 587 of file mjcf-graph.cpp.

◆ parseGeomTree()

void pinocchio::mjcf::details::MjcfGraph::parseGeomTree ( const GeometryType type,
GeometryModel geomModel,
::hpp::fcl::MeshLoaderPtr &  meshLoader 
)

Fill geometry model with all the info taken from the mjcf model file.

Parameters
typeType of geometry to parse (COLLISION or VISUAL)
geomModelgeometry model to fill
meshLoadermesh loader from hpp::fcl

Definition at line 500 of file mjcf-graph-geom.cpp.

◆ parseGraph()

void pinocchio::mjcf::details::MjcfGraph::parseGraph ( )

parse the mjcf file into a graph

Definition at line 724 of file mjcf-graph.cpp.

◆ parseGraphFromXML()

void pinocchio::mjcf::details::MjcfGraph::parseGraphFromXML ( const std::string &  xmlStr)

parse the mjcf file into a graph

Parameters
xmlStrxml file name

Definition at line 764 of file mjcf-graph.cpp.

◆ parseJointAndBody()

void pinocchio::mjcf::details::MjcfGraph::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.

Parameters
elroot of the tree
parentNamename of the parentBody in the robot tree

Definition at line 392 of file mjcf-graph.cpp.

◆ parseKeyFrame()

void pinocchio::mjcf::details::MjcfGraph::parseKeyFrame ( const ptree el)

Parse all the info from the meta tag keyframe.

Parameters
elptree keyframe node

Definition at line 703 of file mjcf-graph.cpp.

◆ parseMaterial()

void pinocchio::mjcf::details::MjcfGraph::parseMaterial ( const ptree el)

Parse all the info from a material node.

Parameters
elptree material node

Definition at line 522 of file mjcf-graph.cpp.

◆ parseMesh()

void pinocchio::mjcf::details::MjcfGraph::parseMesh ( const ptree el)

Parse all the info from a mesh node.

Parameters
elptree mesh node

Definition at line 547 of file mjcf-graph.cpp.

◆ parseRootTree()

void pinocchio::mjcf::details::MjcfGraph::parseRootTree ( )

Fill the pinocchio model with all the infos from the graph.

Definition at line 1018 of file mjcf-graph.cpp.

◆ parseTexture()

void pinocchio::mjcf::details::MjcfGraph::parseTexture ( const ptree el)

Parse all the info from a texture node.

Parameters
elptree texture node

Definition at line 498 of file mjcf-graph.cpp.

Member Data Documentation

◆ bodiesList

VectorOfStrings pinocchio::mjcf::details::MjcfGraph::bodiesList

Definition at line 363 of file mjcf-graph.hpp.

◆ compilerInfo

MjcfCompiler pinocchio::mjcf::details::MjcfGraph::compilerInfo

Definition at line 342 of file mjcf-graph.hpp.

◆ mapOfBodies

BodyMap_t pinocchio::mjcf::details::MjcfGraph::mapOfBodies

Definition at line 346 of file mjcf-graph.hpp.

◆ mapOfClasses

ClassMap_t pinocchio::mjcf::details::MjcfGraph::mapOfClasses

Definition at line 344 of file mjcf-graph.hpp.

◆ mapOfConfigs

ConfigMap_t pinocchio::mjcf::details::MjcfGraph::mapOfConfigs

Definition at line 354 of file mjcf-graph.hpp.

◆ mapOfMaterials

MaterialMap_t pinocchio::mjcf::details::MjcfGraph::mapOfMaterials

Definition at line 348 of file mjcf-graph.hpp.

◆ mapOfMeshes

MeshMap_t pinocchio::mjcf::details::MjcfGraph::mapOfMeshes

Definition at line 350 of file mjcf-graph.hpp.

◆ mapOfTextures

TextureMap_t pinocchio::mjcf::details::MjcfGraph::mapOfTextures

Definition at line 352 of file mjcf-graph.hpp.

◆ modelName

std::string pinocchio::mjcf::details::MjcfGraph::modelName

Definition at line 366 of file mjcf-graph.hpp.

◆ modelPath

std::string pinocchio::mjcf::details::MjcfGraph::modelPath

Definition at line 367 of file mjcf-graph.hpp.

◆ pt

ptree pinocchio::mjcf::details::MjcfGraph::pt

Definition at line 360 of file mjcf-graph.hpp.

◆ referenceConfig

Eigen::VectorXd pinocchio::mjcf::details::MjcfGraph::referenceConfig

Definition at line 357 of file mjcf-graph.hpp.

◆ urdfVisitor

UrdfVisitor& pinocchio::mjcf::details::MjcfGraph::urdfVisitor

Definition at line 373 of file mjcf-graph.hpp.


The documentation for this struct was generated from the following files:


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