gz_compat.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018 Trey Henrichsen, Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef ROSFLIGHT_SIM_GZ_COMPAT_H // Include guard
33 #define ROSFLIGHT_SIM_GZ_COMPAT_H
34 
35 #include <gazebo/gazebo.hh>
36 
37 #if GAZEBO_MAJOR_VERSION >= 8
38 
39 #include "gazebo/common/CommonTypes.hh"
40 
41 using GazeboVector = ignition::math::Vector3d;
42 using GazeboPose = ignition::math::Pose3d;
43 using GazeboQuaternion = ignition::math::Quaterniond;
44 
45 #define GZ_COMPAT_GET_X(VECTOR) (VECTOR).X()
46 #define GZ_COMPAT_GET_Y(VECTOR) (VECTOR).Y()
47 #define GZ_COMPAT_GET_Z(VECTOR) (VECTOR).Z()
48 #define GZ_COMPAT_GET_W(VECTOR) (VECTOR).W() // For quaternions
49 #define GZ_COMPAT_SET_X(VECTOR, VALUE) (VECTOR).X((VALUE))
50 #define GZ_COMPAT_SET_Y(VECTOR, VALUE) (VECTOR).Y((VALUE))
51 #define GZ_COMPAT_SET_Z(VECTOR, VALUE) (VECTOR).Z((VALUE))
52 #define GZ_COMPAT_SET_W(VECTOR, VALUE) (VECTOR).W((VALUE))
53 #define GZ_COMPAT_GET_POS(POSE) (POSE).Pos()
54 #define GZ_COMPAT_GET_ROT(POSE) (POSE).Rot()
55 #define GZ_COMPAT_GET_EULER(QUAT) (QUAT).Euler()
56 #define GZ_COMPAT_GET_SIM_TIME(WORLD_PTR) (WORLD_PTR)->SimTime()
57 #define GZ_COMPAT_GET_RELATIVE_LINEAR_VEL(LINK_PTR) (LINK_PTR)->RelativeLinearVel()
58 #define GZ_COMPAT_GET_WORLD_LINEAR_VEL(LINK_PTR) (LINK_PTR)->WorldLinearVel()
59 #define GZ_COMPAT_GET_RELATIVE_ANGULAR_VEL(LINK_PTR) (LINK_PTR)->RelativeAngularVel()
60 #define GZ_COMPAT_GET_WORLD_COG_POSE(LINK_PTR) (LINK_PTR)->WorldCoGPose()
61 #define GZ_COMPAT_GET_WORLD_POSE(LINK_PTR) (LINK_PTR)->WorldPose()
62 #define GZ_COMPAT_GET_RELATIVE_FORCE(LINK_PTR) (LINK_PTR)->RelativeForce()
63 #define GZ_COMPAT_GET_ENTITY(WORLD_PTR, FRAME_ID_PTR) (WORLD_PTR)->EntityByName((FRAME_ID_PTR))
64 #define GZ_COMPAT_GET_WORLD_LINEAR_ACCEL(LINK_PTR) (LINK_PTR)->WorldLinearAccel()
65 #define GZ_COMPAT_GET_LENGTH(VECTOR) (VECTOR).Length()
66 #define GZ_COMPAT_DISCONNECT_WORLD_UPDATE_BEGIN(CONNECTION) (CONNECTION).reset()
67 #define GZ_COMPAT_GET_GRAVITY(WORLD_PTR) (WORLD_PTR)->Gravity()
68 #define GZ_COMPAT_GET_MASS(INERTIAL_PTR) (INERTIAL_PTR)->Mass()
69 
70 #else // I.E. GAZEBO_MAJOR_VERSION < 8
71 
72 using GazeboVector = gazebo::math::Vector3;
73 using GazeboPose = gazebo::math::Pose;
74 using GazeboQuaternion = gazebo::math::Quaternion;
75 
76 #define GZ_COMPAT_GET_X(VECTOR) (VECTOR).x
77 #define GZ_COMPAT_GET_Y(VECTOR) (VECTOR).y
78 #define GZ_COMPAT_GET_Z(VECTOR) (VECTOR).z
79 #define GZ_COMPAT_GET_W(VECTOR) (VECTOR).w // For quaternions
80 #define GZ_COMPAT_SET_X(VECTOR, VALUE) (VECTOR).x = (VALUE)
81 #define GZ_COMPAT_SET_Y(VECTOR, VALUE) (VECTOR).y = (VALUE)
82 #define GZ_COMPAT_SET_Z(VECTOR, VALUE) (VECTOR).z = (VALUE)
83 #define GZ_COMPAT_SET_W(VECTOR, VALUE) (VECTOR).w = (VALUE)
84 #define GZ_COMPAT_GET_POS(POSE) (POSE).pos
85 #define GZ_COMPAT_GET_ROT(POSE) (POSE).rot
86 #define GZ_COMPAT_GET_EULER(QUAT) (QUAT).GetAsEuler()
87 #define GZ_COMPAT_GET_SIM_TIME(WORLD_PTR) (WORLD_PTR)->GetSimTime()
88 #define GZ_COMPAT_GET_RELATIVE_LINEAR_VEL(LINK_PTR) (LINK_PTR)->GetRelativeLinearVel()
89 #define GZ_COMPAT_GET_WORLD_LINEAR_VEL(LINK_PTR) (LINK_PTR)->GetWorldLinearVel()
90 #define GZ_COMPAT_GET_RELATIVE_ANGULAR_VEL(LINK_PTR) (LINK_PTR)->GetRelativeAngularVel()
91 #define GZ_COMPAT_GET_WORLD_COG_POSE(LINK_PTR) (LINK_PTR)->GetWorldCoGPose()
92 #define GZ_COMPAT_GET_WORLD_POSE(LINK_PTR) (LINK_PTR)->GetWorldPose()
93 #define GZ_COMPAT_GET_RELATIVE_FORCE(LINK_PTR) (LINK_PTR)->GetRelativeForce()
94 #define GZ_COMPAT_GET_ENTITY(WORLD_PTR, FRAME_ID_PTR) (WORLD_PTR)->GetEntity((FRAME_ID_PTR))
95 #define GZ_COMPAT_GET_WORLD_LINEAR_ACCEL(LINK_PTR) (LINK_PTR)->GetWorldLinearAccel()
96 #define GZ_COMPAT_GET_LENGTH(VECTOR) (VECTOR).GetLength()
97 #define GZ_COMPAT_DISCONNECT_WORLD_UPDATE_BEGIN(CONNECTION) \
98  gazebo::event::Events::DisconnectWorldUpdateBegin((CONNECTION))
99 #define GZ_COMPAT_GET_GRAVITY(WORLD_PTR) (WORLD_PTR)->GetPhysicsEngine()->GetGravity()
100 #define GZ_COMPAT_GET_MASS(INERTIAL_PTR) (INERTIAL_PTR)->GetMass()
101 
102 #endif // GAZEBO_MAJOR_VERSION >= 8
103 
104 #endif // Include guard
gazebo::math::Vector3 GazeboVector
Definition: gz_compat.h:72
gazebo::math::Pose GazeboPose
Definition: gz_compat.h:73
gazebo::math::Quaternion GazeboQuaternion
Definition: gz_compat.h:74


rosflight_sim
Author(s): James Jackson, Gary Ellingson, Daniel Koch
autogenerated on Thu Apr 15 2021 05:09:57