DARTTypes.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef GAZEBO_PHYSICS_DART_DARTTYPES_HH_
18 #define GAZEBO_PHYSICS_DART_DARTTYPES_HH_
19 
20 #include <boost/shared_ptr.hpp>
21 #include <ignition/math/Vector3.hh>
22 
23 #include "gazebo/common/Assert.hh"
24 #include "gazebo/math/Pose.hh"
26 #include "gazebo/util/system.hh"
27 
32 namespace gazebo
33 {
34  namespace physics
35  {
36  class DARTPhysics;
37  class DARTModel;
38  class DARTLink;
39  class DARTJoint;
40  class DARTCollision;
41  class DARTRayShape;
43 
44  typedef boost::shared_ptr<DARTPhysics> DARTPhysicsPtr;
45  typedef boost::shared_ptr<DARTModel> DARTModelPtr;
46  typedef boost::shared_ptr<DARTLink> DARTLinkPtr;
47  typedef boost::shared_ptr<DARTJoint> DARTJointPtr;
48  typedef boost::shared_ptr<DARTCollision> DARTCollisionPtr;
49  typedef boost::shared_ptr<DARTRayShape> DARTRayShapePtr;
50  typedef boost::shared_ptr<DARTSurfaceParams> DARTSurfaceParamsPtr;
51 
52  using DARTBodyNodePropPtr =
53  std::shared_ptr<dart::dynamics::BodyNode::Properties>;
54  using DARTJointPropPtr =
55  std::shared_ptr<dart::dynamics::Joint::Properties>;
56 
59 
63  class GZ_PHYSICS_VISIBLE DARTTypes
64  {
66  public: static Eigen::Vector3d ConvVec3(const math::Vector3 &_vec3)
68  {
69 #ifndef _WIN32
70  #pragma GCC diagnostic push
71  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
72 #endif
73  return ConvVec3(_vec3.Ign());
74 #ifndef _WIN32
75  #pragma GCC diagnostic pop
76 #endif
77  }
78 
82  public: static Eigen::Vector3d ConvVec3(
83  const ignition::math::Vector3d &_vec3)
84  {
85  return Eigen::Vector3d(_vec3.X(), _vec3.Y(), _vec3.Z());
86  }
87 
89  public: static math::Vector3 ConvVec3(const Eigen::Vector3d &_vec3)
91  {
92 #ifndef _WIN32
93  #pragma GCC diagnostic push
94  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
95 #endif
96  return ConvVec3Ign(_vec3);
97 #ifndef _WIN32
98  #pragma GCC diagnostic pop
99 #endif
100  }
101 
105  public: static ignition::math::Vector3d ConvVec3Ign(
106  const Eigen::Vector3d &_vec3)
107  {
108  return ignition::math::Vector3d(_vec3.x(), _vec3.y(), _vec3.z());
109  }
110 
112  public: static Eigen::Quaterniond ConvQuat(const math::Quaternion &_quat)
113  GAZEBO_DEPRECATED(8.0)
114  {
115 #ifndef _WIN32
116  #pragma GCC diagnostic push
117  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
118 #endif
119  return ConvQuat(_quat.Ign());
120 #ifndef _WIN32
121  #pragma GCC diagnostic pop
122 #endif
123  }
124 
128  public: static Eigen::Quaterniond ConvQuat(
129  const ignition::math::Quaterniond &_quat)
130  {
131  return Eigen::Quaterniond(_quat.W(), _quat.X(), _quat.Y(), _quat.Z());
132  }
133 
135  public: static math::Quaternion ConvQuat(const Eigen::Quaterniond &_quat)
136  GAZEBO_DEPRECATED(8.0)
137  {
138 #ifndef _WIN32
139  #pragma GCC diagnostic push
140  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
141 #endif
142  return ConvQuatIgn(_quat);
143 #ifndef _WIN32
144  #pragma GCC diagnostic pop
145 #endif
146  }
147 
151  public: static ignition::math::Quaterniond ConvQuatIgn(
152  const Eigen::Quaterniond &_quat)
153  {
154  return ignition::math::Quaterniond(
155  _quat.w(), _quat.x(), _quat.y(), _quat.z());
156  }
157 
159  public: static Eigen::Isometry3d ConvPose(const math::Pose &_pose)
160  GAZEBO_DEPRECATED(8.0)
161  {
162 #ifndef _WIN32
163  #pragma GCC diagnostic push
164  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
165 #endif
166  return ConvPose(_pose.Ign());
167 #ifndef _WIN32
168  #pragma GCC diagnostic pop
169 #endif
170  }
171 
173  public: static Eigen::Isometry3d ConvPose(
174  const ignition::math::Pose3d &_pose)
175  {
176  // Below line doesn't work with 'libeigen3-dev is 3.0.5-1'
177  // return Eigen::Translation3d(ConvVec3(_pose.pos)) *
178  // ConvQuat(_pose.rot);
179 
180  Eigen::Isometry3d res = Eigen::Isometry3d::Identity();
181 
182  res.translation() = ConvVec3(_pose.Pos());
183  res.linear() = Eigen::Matrix3d(ConvQuat(_pose.Rot()));
184 
185  return res;
186  }
187 
189  public: static math::Pose ConvPose(const Eigen::Isometry3d &_T)
190  GAZEBO_DEPRECATED(8.0)
191  {
192 #ifndef _WIN32
193  #pragma GCC diagnostic push
194  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
195 #endif
196  return ConvPoseIgn(_T);
197 #ifndef _WIN32
198  #pragma GCC diagnostic pop
199 #endif
200  }
201 
205  public: static ignition::math::Pose3d ConvPoseIgn(
206  const Eigen::Isometry3d &_T)
207  {
208  ignition::math::Pose3d pose;
209  pose.Pos() = ConvVec3Ign(_T.translation());
210  pose.Rot() = ConvQuatIgn(Eigen::Quaterniond(_T.linear()));
211  return pose;
212  }
213 
220  public: static double InvertThreadPitch(double _pitch)
221  {
222  GZ_ASSERT(std::abs(_pitch) > 0.0,
223  "Zero thread pitch is not allowed.\n");
224 
225  return -2.0 * M_PI / _pitch;
226  }
227  };
228  }
229 }
230 
231 #endif
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