33 #ifndef DART_UTILS_MJCF_DETAIL_INERTIAL_HPP_
34 #define DART_UTILS_MJCF_DETAIL_INERTIAL_HPP_
45 namespace MjcfParser {
84 Eigen::Quaterniond
mQuat{Eigen::Quaterniond::Identity()};
Definition: Compiler.hpp:51
Definition: Inertial.hpp:51
Errors compile(const Compiler &compiler)
Definition: Inertial.cpp:148
void setMass(double mass)
Definition: Inertial.cpp:195
Eigen::Isometry3d mRelativeTransform
Definition: Inertial.hpp:122
Eigen::Vector3d mDiagonalInertia
Definition: Inertial.hpp:128
Eigen::Isometry3d mWorldTransform
Definition: Inertial.hpp:123
void setOffDiagInertia(const Eigen::Vector3d &inertia)
Definition: Inertial.cpp:219
void setWorldTransform(const Eigen::Isometry3d &tf)
Definition: Inertial.cpp:243
const Eigen::Isometry3d & getRelativeTransform() const
Definition: Inertial.cpp:237
const Eigen::Vector3d & getOffDiagInertia() const
Definition: Inertial.cpp:225
double getMass() const
Definition: Inertial.cpp:201
Eigen::Vector3d mOffDiagonalInertia
Definition: Inertial.hpp:129
const Eigen::Isometry3d & getWorldTransform() const
Definition: Inertial.cpp:249
Data mData
Definition: Inertial.hpp:117
void setDiagInertia(const Eigen::Vector3d &inertia)
Definition: Inertial.cpp:207
const Eigen::Vector3d & getDiagInertia() const
Definition: Inertial.cpp:213
Errors read(tinyxml2::XMLElement *element)
Definition: Inertial.cpp:44
double mMass
Mass of the body.
Definition: Inertial.hpp:126
void setRelativeTransform(const Eigen::Isometry3d &tf)
Definition: Inertial.cpp:231
Eigen::Vector3d mPos
Position of the inertial frame.
Definition: Inertial.hpp:120
boost::optional< T > optional
Definition: Optional.hpp:50
std::vector< Error > Errors
Definition: Error.hpp:85
Definition: BulletCollisionDetector.cpp:65
Definition: Inertial.hpp:79
double mMass
Mass of the body.
Definition: Inertial.hpp:107
common::optional< Eigen::Vector3d > mDiagInertia
Diagonal inertia matrix, expressing the body inertia relative to the inertial frame.
Definition: Inertial.hpp:111
Eigen::Vector3d mPos
Position of the inertial frame.
Definition: Inertial.hpp:81
Eigen::Isometry3d mWorldTransform
Definition: Inertial.hpp:104
common::optional< Eigen::Vector4d > mAxisAngle
These are the quantities (x, y, z, a) mentioned above.
Definition: Inertial.hpp:89
Eigen::Isometry3d mRelativeTransform
Definition: Inertial.hpp:103
common::optional< Eigen::Vector3d > mEuler
Rotation angles around three coordinate axes.
Definition: Inertial.hpp:92
Eigen::Quaterniond mQuat
Quaternion.
Definition: Inertial.hpp:84
common::optional< Eigen::Vector3d > mZAxis
The Z axis of the frame.
Definition: Inertial.hpp:101
common::optional< Eigen::Vector6d > mFullInertia
Full inertia matrix M.
Definition: Inertial.hpp:114
common::optional< Eigen::Vector6d > mXYAxes
The first 3 numbers are the X axis of the frame.
Definition: Inertial.hpp:98