dart physics engine wrapper More...
Files | |
| file | DARTTypes.hh |
| DART wrapper forward declarations and typedefs. | |
Classes | |
| class | DARTBallJoint |
| An DARTBallJoint. More... | |
| class | DARTBoxShape |
| DART Box shape. More... | |
| class | DARTCollision |
| Base class for all DART collisions. More... | |
| class | DARTCylinderShape |
| DART cylinder shape. More... | |
| class | DARTFixedJoint |
| A single axis hinge joint. More... | |
| class | DARTHeightmapShape |
| DART Height map collision. More... | |
| class | DARTHinge2Joint |
| A two axis hinge joint. More... | |
| class | DARTHingeJoint |
| A single axis hinge joint. More... | |
| class | DARTJoint |
| DART joint interface. More... | |
| class | DARTLink |
| DART Link class. More... | |
| class | DARTMesh |
| Triangle mesh collision helper class. More... | |
| class | DARTMeshShape |
| Triangle mesh collision. More... | |
| class | DARTModel |
| DART model class. More... | |
| class | DARTMultiRayShape |
| DART specific version of MultiRayShape. More... | |
| class | DARTPhysics |
| DART physics engine. More... | |
| class | DARTPlaneShape |
| An DART Plane shape. More... | |
| class | DARTPolylineShape |
| DART polyline shape. More... | |
| class | DARTRayShape |
| Ray collision. More... | |
| class | DARTScrewJoint |
| A screw joint. More... | |
| class | DARTSliderJoint |
| A slider joint. More... | |
| class | DARTSphereShape |
| A DART sphere shape. More... | |
| class | DARTSurfaceParams |
| DART surface parameters. More... | |
| class | DARTTypes |
| A set of functions for converting between the math types used by gazebo and dart. More... | |
| class | DARTUniversalJoint |
| A universal joint. More... | |
Functions | |
| static Eigen::Isometry3d | ConvPose (const math::Pose &_pose) |
| static math::Pose | ConvPose (const Eigen::Isometry3d &_T) |
| static Eigen::Quaterniond | ConvQuat (const math::Quaternion &_quat) |
| static math::Quaternion | ConvQuat (const Eigen::Quaterniond &_quat) |
| static Eigen::Vector3d | ConvVec3 (const math::Vector3 &_vec3) |
| static math::Vector3 | ConvVec3 (const Eigen::Vector3d &_vec3) |
| static double | InvertThreadPitch (double _pitch) |
| Invert thread pitch to match the different definitions of thread pitch in Gazebo and DART. More... | |
dart physics engine wrapper
DART physics engine wrapper.
|
inlinestatic |
References DARTTypes::ConvQuat(), DARTTypes::ConvVec3(), Pose::pos, and Pose::rot.
|
inlinestatic |
References DARTTypes::ConvQuat(), DARTTypes::ConvVec3(), Pose::pos, and Pose::rot.
|
inlinestatic |
References Quaternion::w, Quaternion::x, Quaternion::y, and Quaternion::z.
Referenced by DARTTypes::ConvPose().
|
inlinestatic |
|
inlinestatic |
References Vector3::x, Vector3::y, and Vector3::z.
Referenced by DARTTypes::ConvPose().
|
inlinestatic |
|
inlinestatic |
Invert thread pitch to match the different definitions of thread pitch in Gazebo and DART.
[Definitions of thread pitch] Gazebo: NEGATIVE angular motion per linear motion. DART : linear motion per single rotation.
References GZ_ASSERT.