DART
6.10.1
|
Intermediate raw data read from the XML file. More...
Public Attributes | |
common::optional< std::string > | mName |
Name of the Site. More... | |
GeomType | mType {GeomType::SPHERE} |
Type of Siteetric shape. More... | |
int | mGroup {0} |
Eigen::Vector3d | mSize {Eigen::Vector3d::Zero()} |
Site size parameters. More... | |
Eigen::Vector4d | mRGBA {Eigen::Vector4d(0.5, 0.5, 0.5, 1)} |
common::optional< Eigen::Vector6d > | mFromTo |
This attribute can only be used with capsule, cylinder, ellipsoid and box Sites. More... | |
Eigen::Vector3d | mPos {Eigen::Vector3d::Zero()} |
Position of the Site 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::Vector6d > | mXYAxes |
The first 3 numbers are the X axis of the frame. More... | |
common::optional< Eigen::Vector3d > | mZAxis |
The Z axis of the frame. More... | |
Intermediate raw data read from the XML file.
For the details, see http://www.mujoco.org/book/XMLreference.html#Site
common::optional<Eigen::Vector4d> dart::utils::MjcfParser::detail::Site::Data::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.
common::optional<Eigen::Vector3d> dart::utils::MjcfParser::detail::Site::Data::mEuler |
Rotation angles around three coordinate axes.
common::optional<Eigen::Vector6d> dart::utils::MjcfParser::detail::Site::Data::mFromTo |
This attribute can only be used with capsule, cylinder, ellipsoid and box Sites.
It provides an alternative specification of the Site length as well as the frame position and orientation.
int dart::utils::MjcfParser::detail::Site::Data::mGroup {0} |
common::optional<std::string> dart::utils::MjcfParser::detail::Site::Data::mName |
Name of the Site.
Eigen::Vector3d dart::utils::MjcfParser::detail::Site::Data::mPos {Eigen::Vector3d::Zero()} |
Position of the Site frame, in local or global coordinates as determined by the coordinate attribute of compiler.
Eigen::Quaterniond dart::utils::MjcfParser::detail::Site::Data::mQuat {Eigen::Quaterniond::Identity()} |
Quaternion.
Eigen::Vector4d dart::utils::MjcfParser::detail::Site::Data::mRGBA {Eigen::Vector4d(0.5, 0.5, 0.5, 1)} |
Eigen::Vector3d dart::utils::MjcfParser::detail::Site::Data::mSize {Eigen::Vector3d::Zero()} |
Site size parameters.
GeomType dart::utils::MjcfParser::detail::Site::Data::mType {GeomType::SPHERE} |
Type of Siteetric shape.
common::optional<Eigen::Vector6d> dart::utils::MjcfParser::detail::Site::Data::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.
common::optional<Eigen::Vector3d> dart::utils::MjcfParser::detail::Site::Data::mZAxis |
The Z axis of the frame.