Struct MjcfGraph
Defined in File mjcf-graph.hpp
Struct Documentation
-
struct MjcfGraph
The graph which contains all information taken from the mjcf file.
Public Types
-
typedef boost::property_tree::ptree ptree
-
typedef std::vector<std::string> VectorOfStrings
-
typedef std::unordered_map<std::string, MjcfMaterial> MaterialMap_t
-
typedef std::unordered_map<std::string, MjcfTexture> TextureMap_t
-
typedef std::unordered_map<std::string, Eigen::VectorXd> ConfigMap_t
-
typedef std::map<std::string, MjcfEquality> EqualityMap_t
-
typedef pinocchio::urdf::details::UrdfVisitor<double, 0, ::pinocchio::JointCollectionDefaultTpl> UrdfVisitor
Public Functions
-
inline MjcfGraph(UrdfVisitor &urdfVisitor, const std::string &modelPath)
graph constructor
- Parameters:
urdfVisitor –
-
SE3 convertPosition(const ptree &el) const
Convert pose of an mjcf element into SE3.
- Parameters:
el – ptree element with all the pose element
- Returns:
pose in SE3
-
Inertia convertInertiaFromMjcf(const ptree &el) const
Convert Inertia of an mjcf element into Inertia model of pinocchio.
- Parameters:
el – ptree element with all the inertial information
- Returns:
Inertia element in pinocchio
-
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 use.
- Parameters:
el – ptree element. Root of the default
-
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.
- Parameters:
el – root of the tree
parentName – name of the parentBody in the robot tree
-
void parseCompiler(const ptree &el)
Parse all the info from the compile node into compilerInfo.
- Parameters:
el – ptree compile node
-
void parseTexture(const ptree &el)
Parse all the info from a texture node.
- Parameters:
el – ptree texture node
-
void parseMaterial(const ptree &el)
Parse all the info from a material node.
- Parameters:
el – ptree material node
-
void parseMesh(const ptree &el)
Parse all the info from a mesh node.
- Parameters:
el – ptree mesh node
-
void parseAsset(const ptree &el)
Parse all the info from the meta tag asset (mesh, material, texture)
- Parameters:
el – ptree texture node
-
void parseKeyFrame(const ptree &el)
Parse all the info from the meta tag keyframe.
- Parameters:
el – ptree keyframe node
-
void parseEquality(const ptree &el)
Parse all the info from the equality tag.
- Parameters:
el – ptree equality node
-
void parseGraph()
parse the mjcf file into a graph
-
void parseGraphFromXML(const std::string &xmlStr)
parse the mjcf file into a graph
- Parameters:
xmlStr – xml file name
-
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.
- Template Parameters:
TypeX – joint with axis X
TypeY – joint with axis Y
TypeZ – joint with axis Z
TypeUnaligned – joint with axis unaligned
- Parameters:
axis – axis of the joint
- Returns:
one of the joint with the right axis
-
void addSoloJoint(const MjcfJoint &jointInfo, const MjcfBody ¤tBody, SE3 &bodyInJoint)
Add a joint to the model. only needed when a body has a solo joint child.
- Parameters:
jointInfo – The joint to add to the tree
currentBody – The body associated with the joint
bodyInJoint – Position of the body wrt to its joint
-
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.
- Parameters:
nameOfBody – Name of the body to add
-
void parseRootTree()
Fill the pinocchio model with all the infos from the graph.
-
void fillReferenceConfig(const MjcfBody ¤tBody)
Fill reference configuration for a body and all it’s associated dof.
- Parameters:
currentBody – body to check
-
void addKeyFrame(const Eigen::VectorXd &keyframe, const std::string &keyName)
Add a keyframe to the model (ie reference configuration)
- Parameters:
keyframe – Keyframe to add
keyName – Name of the keyframe
- void parseContactInformation (const Model &model, PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) &contact_models)
Parse the equality constraints and add them to the model.
- Parameters:
model – Model to add the constraints to
contact_models – Vector of contact models to add the constraints to
-
void parseGeomTree(const GeometryType &type, GeometryModel &geomModel, ::hpp::fcl::MeshLoaderPtr &meshLoader)
Fill geometry model with all the info taken from the mjcf model file.
- Parameters:
type – Type of geometry to parse (COLLISION or VISUAL)
geomModel – geometry model to fill
meshLoader – mesh loader from hpp::fcl
Public Members
-
MjcfCompiler compilerInfo
-
ClassMap_t mapOfClasses
-
MaterialMap_t mapOfMaterials
-
TextureMap_t mapOfTextures
-
ConfigMap_t mapOfConfigs
-
EqualityMap_t mapOfEqualities
-
Eigen::VectorXd referenceConfig
-
VectorOfStrings bodiesList
-
std::string modelName
-
std::string modelPath
-
UrdfVisitor &urdfVisitor
-
typedef boost::property_tree::ptree ptree