DART  6.10.1
dart::utils::MjcfParser::detail::BodyAttributes Struct Referencefinal

Intermediate raw data read from the XML file. More...

#include <BodyAttributes.hpp>

Public Attributes

common::optional< std::string > mName
 Name of the body. More...
 
common::optional< std::string > mChildClass
 If this attribute is present, all descendant elements that admit a defaults class will use the class specified here, unless they specify their own class or another body with a childclass attribute is encountered along the chain of nested bodies. More...
 
bool mMocap {false}
 If this attribute is "true", the body is labeled as a mocap body. More...
 
common::optional< Eigen::Vector3d > mPos
 The 3D position of the body frame, in local or global coordinates as determined by the coordinate attribute of compiler. More...
 
Eigen::Quaterniond mQuat {Eigen::Quaterniond::Identity()}
 Quaternion. More...
 
common::optional< Eigen::Vector4d > mAxisAngle
 These are the quantities (x, y, z, a) mentioned above. More...
 
common::optional< Eigen::Vector3d > mEuler
 Rotation angles around three coordinate axes. More...
 
common::optional< Eigen::Vector6dmXYAxes
 The first 3 numbers are the X axis of the frame. More...
 
common::optional< Eigen::Vector3d > mZAxis
 The Z axis of the frame. More...
 
Eigen::VectorXd mUser
 
common::optional< InertialmInertial
 

Detailed Description

Intermediate raw data read from the XML file.

For the details, see http://www.mujoco.org/book/XMLreference.html#body

Member Data Documentation

◆ mAxisAngle

common::optional<Eigen::Vector4d> dart::utils::MjcfParser::detail::BodyAttributes::mAxisAngle

These are the quantities (x, y, z, a) mentioned above.

The last number is the angle of rotation, in degrees or radians as specified by the angle attribute of compiler.

◆ mChildClass

common::optional<std::string> dart::utils::MjcfParser::detail::BodyAttributes::mChildClass

If this attribute is present, all descendant elements that admit a defaults class will use the class specified here, unless they specify their own class or another body with a childclass attribute is encountered along the chain of nested bodies.

◆ mEuler

common::optional<Eigen::Vector3d> dart::utils::MjcfParser::detail::BodyAttributes::mEuler

Rotation angles around three coordinate axes.

The sequence of axes around which these rotations are applied is determined by the eulerseq attribute of compiler and is the same for the entire model.

◆ mInertial

common::optional<Inertial> dart::utils::MjcfParser::detail::BodyAttributes::mInertial

◆ mMocap

bool dart::utils::MjcfParser::detail::BodyAttributes::mMocap {false}

If this attribute is "true", the body is labeled as a mocap body.

◆ mName

common::optional<std::string> dart::utils::MjcfParser::detail::BodyAttributes::mName

Name of the body.

◆ mPos

common::optional<Eigen::Vector3d> dart::utils::MjcfParser::detail::BodyAttributes::mPos

The 3D position of the body frame, in local or global coordinates as determined by the coordinate attribute of compiler.

◆ mQuat

Eigen::Quaterniond dart::utils::MjcfParser::detail::BodyAttributes::mQuat {Eigen::Quaterniond::Identity()}

Quaternion.

◆ mUser

Eigen::VectorXd dart::utils::MjcfParser::detail::BodyAttributes::mUser

◆ mXYAxes

common::optional<Eigen::Vector6d> dart::utils::MjcfParser::detail::BodyAttributes::mXYAxes

The first 3 numbers are the X axis of the frame.

The next 3 numbers are the Y axis of the frame, which is automatically made orthogonal to the X axis. The Z axis is then defined as the cross-product of the X and Y axes.

◆ mZAxis

common::optional<Eigen::Vector3d> dart::utils::MjcfParser::detail::BodyAttributes::mZAxis

The Z axis of the frame.