33 #ifndef DART_UTILS_MJCF_DETAIL_GEOMATTRIBUTES_HPP_
34 #define DART_UTILS_MJCF_DETAIL_GEOMATTRIBUTES_HPP_
47 namespace MjcfParser {
71 Eigen::Vector3d
mSize{Eigen::Vector3d::Zero()};
73 Eigen::Vector4d
mRGBA{Eigen::Vector4d(0.5, 0.5, 0.5, 1)};
75 Eigen::Vector3d
mFriction{Eigen::Vector3d(1, 0.005, 0.0001)};
103 Eigen::Vector3d
mPos{Eigen::Vector3d::Zero()};
106 Eigen::Quaterniond
mQuat{Eigen::Quaterniond::Identity()};
133 GeomAttributes& attributes, tinyxml2::XMLElement* element);
boost::optional< T > optional
Definition: Optional.hpp:50
GeomType
Definition: Types.hpp:119
Errors appendGeomAttributes(GeomAttributes &attributes, tinyxml2::XMLElement *element)
Definition: GeomAttributes.cpp:44
std::vector< Error > Errors
Definition: Error.hpp:85
Definition: BulletCollisionDetector.cpp:65
Intermediate raw data read from the XML file.
Definition: GeomAttributes.hpp:53
common::optional< Eigen::Vector4d > mAxisAngle
These are the quantities (x, y, z, a) mentioned above.
Definition: GeomAttributes.hpp:111
double mSolMix
Weight used for averaging of contact parameters, and interacts with the priority attribute.
Definition: GeomAttributes.hpp:85
double mDensity
Material density used to compute the geom mass and inertia.
Definition: GeomAttributes.hpp:81
int mConType
Definition: GeomAttributes.hpp:60
double mGap
This attribute is used to enable the generation of inactive contacts, i.e.
Definition: GeomAttributes.hpp:94
common::optional< Eigen::Vector6d > mXYAxes
The first 3 numbers are the X axis of the frame.
Definition: GeomAttributes.hpp:120
int mConDim
Definition: GeomAttributes.hpp:64
common::optional< Eigen::Vector3d > mEuler
Rotation angles around three coordinate axes.
Definition: GeomAttributes.hpp:114
common::optional< std::string > mHField
Definition: GeomAttributes.hpp:125
common::optional< std::string > mName
Name of the geom.
Definition: GeomAttributes.hpp:55
Eigen::Vector3d mPos
Position of the geom frame, in local or global coordinates as determined by the coordinate attribute ...
Definition: GeomAttributes.hpp:103
common::optional< double > mMass
Mass.
Definition: GeomAttributes.hpp:78
int mConAffinity
Definition: GeomAttributes.hpp:62
Eigen::Vector4d mRGBA
Definition: GeomAttributes.hpp:73
GeomType mType
Type of geometric shape.
Definition: GeomAttributes.hpp:58
Eigen::Vector3d mSize
Geom size parameters.
Definition: GeomAttributes.hpp:71
double mMargin
Distance threshold below which contacts are detected and included in the global array mjData....
Definition: GeomAttributes.hpp:89
Eigen::Quaterniond mQuat
Quaternion.
Definition: GeomAttributes.hpp:106
int mPriority
Definition: GeomAttributes.hpp:68
int mGroup
Definition: GeomAttributes.hpp:66
common::optional< std::string > mMesh
Definition: GeomAttributes.hpp:127
Eigen::Vector3d mFriction
Definition: GeomAttributes.hpp:75
double mFitScale
Definition: GeomAttributes.hpp:129
common::optional< Eigen::Vector6d > mFromTo
This attribute can only be used with capsule, cylinder, ellipsoid and box geoms.
Definition: GeomAttributes.hpp:99
common::optional< Eigen::Vector3d > mZAxis
The Z axis of the frame.
Definition: GeomAttributes.hpp:123