17 #ifndef GAZEBO_PHYSICS_DART_DARTTYPES_HH_
18 #define GAZEBO_PHYSICS_DART_DARTTYPES_HH_
20 #include <boost/shared_ptr.hpp>
21 #include <ignition/math/Vector3.hh>
53 std::shared_ptr<dart::dynamics::BodyNode::Properties>;
55 std::shared_ptr<dart::dynamics::Joint::Properties>;
70 #pragma GCC diagnostic push
71 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
73 return ConvVec3(_vec3.Ign());
75 #pragma GCC diagnostic pop
83 const ignition::math::Vector3d &_vec3)
85 return Eigen::Vector3d(_vec3.X(), _vec3.Y(), _vec3.Z());
93 #pragma GCC diagnostic push
94 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
96 return ConvVec3Ign(_vec3);
98 #pragma GCC diagnostic pop
106 const Eigen::Vector3d &_vec3)
108 return ignition::math::Vector3d(_vec3.x(), _vec3.y(), _vec3.z());
116 #pragma GCC diagnostic push
117 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
119 return ConvQuat(_quat.Ign());
121 #pragma GCC diagnostic pop
129 const ignition::math::Quaterniond &_quat)
131 return Eigen::Quaterniond(_quat.W(), _quat.X(), _quat.Y(), _quat.Z());
139 #pragma GCC diagnostic push
140 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
142 return ConvQuatIgn(_quat);
144 #pragma GCC diagnostic pop
152 const Eigen::Quaterniond &_quat)
154 return ignition::math::Quaterniond(
155 _quat.w(), _quat.x(), _quat.y(), _quat.z());
163 #pragma GCC diagnostic push
164 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
166 return ConvPose(_pose.Ign());
168 #pragma GCC diagnostic pop
174 const ignition::math::Pose3d &_pose)
180 Eigen::Isometry3d res = Eigen::Isometry3d::Identity();
182 res.translation() = ConvVec3(_pose.Pos());
183 res.linear() = Eigen::Matrix3d(ConvQuat(_pose.Rot()));
193 #pragma GCC diagnostic push
194 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
196 return ConvPoseIgn(_T);
198 #pragma GCC diagnostic pop
206 const Eigen::Isometry3d &_T)
208 ignition::math::Pose3d pose;
209 pose.Pos() = ConvVec3Ign(_T.translation());
210 pose.Rot() = ConvQuatIgn(Eigen::Quaterniond(_T.linear()));
223 "Zero thread pitch is not allowed.\n");
225 return -2.0 * M_PI / _pitch;
boost::shared_ptr< DARTJoint > DARTJointPtr
Definition: DARTTypes.hh:47
static Eigen::Isometry3d ConvPose(const math::Pose &_pose) GAZEBO_DEPRECATED(8.0)
Definition: DARTTypes.hh:159
static ignition::math::Quaterniond ConvQuatIgn(const Eigen::Quaterniond &_quat)
Convert eigen quaternion to ignition quaternion.
Definition: DARTTypes.hh:151
#define GZ_ASSERT(_expr, _msg)
This macro define the standard way of launching an exception inside gazebo.
Definition: Assert.hh:24
static Eigen::Quaterniond ConvQuat(const ignition::math::Quaterniond &_quat)
Convert ignition quaternion to eigen quaternion.
Definition: DARTTypes.hh:128
static Eigen::Quaterniond ConvQuat(const math::Quaternion &_quat) GAZEBO_DEPRECATED(8.0)
Definition: DARTTypes.hh:112
static Eigen::Isometry3d ConvPose(const ignition::math::Pose3d &_pose)
Definition: DARTTypes.hh:173
Encapsulates a position and rotation in three space.
Definition: Pose.hh:42
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:44
boost::shared_ptr< DARTModel > DARTModelPtr
Definition: DARTTypes.hh:45
static double InvertThreadPitch(double _pitch)
Invert thread pitch to match the different definitions of thread pitch in Gazebo and DART...
Definition: DARTTypes.hh:220
static ignition::math::Vector3d ConvVec3Ign(const Eigen::Vector3d &_vec3)
Convert eigen vector3d to ignition math vector3d.
Definition: DARTTypes.hh:105
DART surface parameters.
Definition: DARTSurfaceParams.hh:38
boost::shared_ptr< DARTLink > DARTLinkPtr
Definition: DARTTypes.hh:46
static Eigen::Vector3d ConvVec3(const ignition::math::Vector3d &_vec3)
Convert ignition math vector3d to eigen vector3d.
Definition: DARTTypes.hh:82
static math::Vector3 ConvVec3(const Eigen::Vector3d &_vec3) GAZEBO_DEPRECATED(8.0)
Definition: DARTTypes.hh:89
static math::Pose ConvPose(const Eigen::Isometry3d &_T) GAZEBO_DEPRECATED(8.0)
Definition: DARTTypes.hh:189
boost::shared_ptr< DARTRayShape > DARTRayShapePtr
Definition: DARTTypes.hh:49
static math::Quaternion ConvQuat(const Eigen::Quaterniond &_quat) GAZEBO_DEPRECATED(8.0)
Definition: DARTTypes.hh:135
boost::shared_ptr< DARTPhysics > DARTPhysicsPtr
Definition: DARTTypes.hh:42
std::shared_ptr< dart::dynamics::BodyNode::Properties > DARTBodyNodePropPtr
Definition: DARTTypes.hh:53
A quaternion class.
Definition: Quaternion.hh:48
std::shared_ptr< dart::dynamics::Joint::Properties > DARTJointPropPtr
Definition: DARTTypes.hh:55
boost::shared_ptr< DARTCollision > DARTCollisionPtr
Definition: DARTTypes.hh:48
boost::shared_ptr< DARTSurfaceParams > DARTSurfaceParamsPtr
Definition: DARTTypes.hh:50
static Eigen::Vector3d ConvVec3(const math::Vector3 &_vec3) GAZEBO_DEPRECATED(8.0)
Definition: DARTTypes.hh:66
#define GAZEBO_DEPRECATED(version)
Definition: system.hh:302
static ignition::math::Pose3d ConvPoseIgn(const Eigen::Isometry3d &_T)
Convert eigen iosmetry3d to ignition math pose3d.
Definition: DARTTypes.hh:205
A set of functions for converting between the math types used by gazebo and dart. ...
Definition: DARTTypes.hh:63