ros.h
Go to the documentation of this file.
1 /**************************************************************************/ /**
2  * @brief ROS support messages.
3  * @file
4  ******************************************************************************/
5 
6 #pragma once
7 
8 namespace point_one {
9 namespace fusion_engine {
10 namespace messages {
11 namespace ros {
12 
13 // Enforce 4-byte alignment and packing of all data structures and values so
14 // that floating point values are aligned on platforms that require it.
15 #pragma pack(push, 4)
16 
17 /**
18  * @defgroup ros_messages ROS Support Message Definitions
19  * @brief Messages designed for direct translation to ROS.
20  * @ingroup messages
21  *
22  * The messages defined in this file are intended to be translated into their
23  * corresponding ROS message structures where ROS integration is needed.
24  *
25  * @note
26  * The messages defined here are _not_ guaranteed to be byte-compatible with ROS
27  * messages. They are designed to have the same or similar content, which can be
28  * easily copied into a ROS message.
29  *
30  * See also @ref messages.
31  */
32 
33 /**
34  * @brief ROS `Pose` message (MessageType::ROS_POSE).
35  * @ingroup ros_messages
36  *
37  * See http://docs.ros.org/api/geometry_msgs/html/msg/Pose.html.
38  */
39 struct PoseMessage {
40  /** The time of the message, in P1 time (beginning at power-on). */
42 
43  /**
44  * The relative change in ENU position since the time of the first @ref
45  * PoseMessage, resolved in the local ENU frame at the time of the first @ref
46  * PoseMessage.
47  *
48  * @warning
49  * The [ROS Pose message API documentation](
50  * http://docs.ros.org/api/geometry_msgs/html/msg/Pose.html)
51  * does not currently define the origin or reference frame of its position
52  * field. Using the Novatel SPAN driver as a reference
53  * (http://docs.ros.org/api/novatel_span_driver/html/publisher_8py_source.html),
54  * we have chosen to report a relative ENU position. Absolute world position
55  * is available in the @ref GPSFixMessage and @ref messages::PoseMessage
56  * classes.
57  */
58  double position_rel_m[3] = {NAN, NAN, NAN};
59 
60  /**
61  * The platform body orientation with respect to the local ENU frame,
62  * represented as a quaternion with the scalar component last (x, y, z, w).
63  */
64  double orientation[4] = {NAN, NAN, NAN, NAN};
65 };
66 
67 /**
68  * @brief ROS `GPSFix` message (MessageType::ROS_GPS_FIX).
69  * @ingroup ros_messages
70  *
71  * See http://docs.ros.org/api/gps_common/html/msg/GPSFix.html.
72  */
73 struct GPSFixMessage {
74  /**
75  * @defgroup ros_covariance_type ROS Covariance Type Values
76  * @{
77  */
78  static const uint8_t COVARIANCE_TYPE_UNKNOWN = 0;
79  static const uint8_t COVARIANCE_TYPE_APPROXIMATED = 1;
80  static const uint8_t COVARIANCE_TYPE_DIAGONAL_KNOWN = 2;
81  static const uint8_t COVARIANCE_TYPE_KNOWN = 3;
82  /** @} */
83 
84  /** The time of the message, in P1 time (beginning at power-on). */
86 
87  /**
88  * @name WGS-84 Geodetic Position
89  * @{
90  */
91 
92  /**
93  * The WGS-84 geodetic latitude (in degrees).
94  */
95  double latitude_deg = NAN;
96 
97  /**
98  * The WGS-84 geodetic longitude (in degrees).
99  */
100  double longitude_deg = NAN;
101 
102  /**
103  * The WGS-84 altitude above the ellipsoid (in meters).
104  */
105  double altitude_m = NAN;
106 
107  /** @} */
108 
109  /**
110  * @name Velocity
111  * @{
112  */
113 
114  /**
115  * The vehicle direction from north (in degrees).
116  */
117  double track_deg = NAN;
118 
119  /**
120  * The vehicle ground speed (in meters/second).
121  */
122  double speed_mps = NAN;
123 
124  /**
125  * The vehicle vertical speed (in meters/second).
126  */
127  double climb_mps = NAN;
128 
129  /** @} */
130 
131  /**
132  * @name Vehicle Orientation
133  *
134  * @warning
135  * The pitch/roll/dip field definition listed in the
136  * [ROS GPSFix message definition](http://docs.ros.org/api/gps_common/html/msg/GPSFix.html)
137  * uses non-standard terminology, and the order of the Euler angles is not
138  * explicitly defined. We do not currently support this field. See @ref
139  * PoseMessage::orientation or @ref messages::PoseMessage::ypr_deg instead.
140  *
141  * @{
142  */
143 
144  /**
145  * The platform pitch angle (in degrees).
146  */
147  double pitch_deg = NAN;
148 
149  /**
150  * The platform roll angle (in degrees).
151  */
152  double roll_deg = NAN;
153 
154  /**
155  * The platform dip angle (in degrees).
156  */
157  double dip_deg = NAN;
158 
159  /** @} */
160 
161  /** The GPS time of the message (in seconds), referenced to 1980/1/6. */
162  double gps_time = NAN;
163 
164  /**
165  * @name Dilution Of Precision
166  * @{
167  */
168 
169  double gdop = NAN; ///< Geometric (position + time) DOP.
170  double pdop = NAN; ///< Positional (3D) DOP.
171  double hdop = NAN; ///< Horizontal DOP.
172  double vdop = NAN; ///< Vertical DOP.
173  double tdop = NAN; ///< Time DOP.
174 
175  /** @} */
176 
177  /**
178  * @name Measurement Uncertainty (95% Confidence)
179  * @{
180  */
181 
182  /** Spherical position uncertainty (in meters) [epe] */
183  double err_3d_m = NAN;
184 
185  /** Horizontal position uncertainty (in meters) [eph] */
186  double err_horiz_m = NAN;
187 
188  /** Vertical position uncertainty (in meters) [epv] */
189  double err_vert_m = NAN;
190 
191  /** Track uncertainty (in degrees) [epd] */
192  double err_track_deg = NAN;
193 
194  /** Ground speed uncertainty (in meters/second) [eps] */
195  double err_speed_mps = NAN;
196 
197  /** Vertical speed uncertainty (in meters/second) [epc] */
198  double err_climb_mps = NAN;
199 
200  /** Time uncertainty (in seconds) [ept] */
201  double err_time_sec = NAN;
202 
203  /** Pitch uncertainty (in degrees) */
204  double err_pitch_deg = NAN;
205 
206  /** Roll uncertainty (in degrees) */
207  double err_roll_deg = NAN;
208 
209  /** Dip uncertainty (in degrees) */
210  double err_dip_deg = NAN;
211 
212  /** @} */
213 
214  /**
215  * @name Position Covariance
216  * @{
217  */
218 
219  /**
220  * The 3x3 position covariance matrix (in m^2), resolved in the local ENU
221  * frame. Values are stored in row-major order.
222  */
223  double position_covariance_m2[9] = {NAN};
224 
225  /**
226  * The method in which @ref position_covariance_m2 was populated. See @ref
227  * ros_covariance_type.
228  */
230 
231  /** @} */
232 
233  uint8_t reserved[3] = {0};
234 };
235 
236 /**
237  * @brief ROS `Imu` message (MessageType::ROS_IMU).
238  * @ingroup ros_messages
239  *
240  * If any of the data elements are not available (e.g., IMU doesn't produce an
241  * orientation estimate), they will be set to 0 and their associated covariance
242  * matrices will be set to -1.
243  *
244  * See http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html.
245  *
246  * @note
247  * The data contained in this message has been corrected for accelerometer and
248  * gyro biases and scale factors, and has been rotated into the vehicle body
249  * frame from the original IMU orientation using the FusionEngine sensor
250  * calibration data.
251  */
252 struct IMUMessage {
253  /** The time of the message, in P1 time (beginning at power-on). */
255 
256  /**
257  * The platform body orientation with respect to the local ENU frame,
258  * represented as a quaternion with the scalar component last (x, y, z, w).
259  */
260  double orientation[4] = {NAN, NAN, NAN, NAN};
261 
262  /**
263  * Orientation covariance matrix. Set to -1 if not available.
264  */
265  double orientation_covariance[9] = {-1};
266 
267  /**
268  * Vehicle x/y/z rate of rotation (in radians/second), resolved in the body
269  * frame.
270  */
271  double angular_velocity_rps[3] = {NAN, NAN, NAN};
272 
273  /**
274  * Vehicle rate of rotation covariance matrix. Set to -1 if not available.
275  */
276  double angular_velocity_covariance[9] = {-1};
277 
278  /**
279  * Vehicle x/y/z linear acceleration (in meters/second^2), resolved in the
280  * body frame.
281  */
282  double acceleration_mps2[3] = {NAN, NAN, NAN};
283 
284  /**
285  * Vehicle x/y/z acceleration covariance matrix. Set to -1 if not available.
286  */
287  double acceleration_covariance[9] = {-1};
288 };
289 
290 #pragma pack(pop)
291 
292 } // namespace ros
293 } // namespace messages
294 } // namespace fusion_engine
295 } // namespace point_one
double dip_deg
The platform dip angle (in degrees).
Definition: ros.h:157
static const uint8_t COVARIANCE_TYPE_KNOWN
Definition: ros.h:81
double track_deg
The vehicle direction from north (in degrees).
Definition: ros.h:117
double position_rel_m[3]
The relative change in ENU position since the time of the first PoseMessage, resolved in the local EN...
Definition: ros.h:58
double acceleration_mps2[3]
Vehicle x/y/z linear acceleration (in meters/second^2), resolved in the body frame.
Definition: ros.h:282
static const uint8_t COVARIANCE_TYPE_APPROXIMATED
Definition: ros.h:79
double latitude_deg
The WGS-84 geodetic latitude (in degrees).
Definition: ros.h:95
double err_horiz_m
Horizontal position uncertainty (in meters) [eph].
Definition: ros.h:186
double err_roll_deg
Roll uncertainty (in degrees)
Definition: ros.h:207
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: ros.h:41
double angular_velocity_covariance[9]
Vehicle rate of rotation covariance matrix.
Definition: ros.h:276
double err_time_sec
Time uncertainty (in seconds) [ept].
Definition: ros.h:201
double acceleration_covariance[9]
Vehicle x/y/z acceleration covariance matrix.
Definition: ros.h:287
ROS Imu message (MessageType::ROS_IMU).
Definition: ros.h:252
double err_track_deg
Track uncertainty (in degrees) [epd].
Definition: ros.h:192
double hdop
Horizontal DOP.
Definition: ros.h:171
static const uint8_t COVARIANCE_TYPE_UNKNOWN
Definition: ros.h:78
double orientation_covariance[9]
Orientation covariance matrix.
Definition: ros.h:265
double pdop
Positional (3D) DOP.
Definition: ros.h:170
double longitude_deg
The WGS-84 geodetic longitude (in degrees).
Definition: ros.h:100
double speed_mps
The vehicle ground speed (in meters/second).
Definition: ros.h:122
double tdop
Time DOP.
Definition: ros.h:173
Definition: crc.cc:49
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: ros.h:254
ROS GPSFix message (MessageType::ROS_GPS_FIX).
Definition: ros.h:73
double gps_time
The GPS time of the message (in seconds), referenced to 1980/1/6.
Definition: ros.h:162
double orientation[4]
The platform body orientation with respect to the local ENU frame, represented as a quaternion with t...
Definition: ros.h:64
double err_climb_mps
Vertical speed uncertainty (in meters/second) [epc].
Definition: ros.h:198
double err_pitch_deg
Pitch uncertainty (in degrees)
Definition: ros.h:204
double pitch_deg
The platform pitch angle (in degrees).
Definition: ros.h:147
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: ros.h:85
ROS Pose message (MessageType::ROS_POSE).
Definition: ros.h:39
double vdop
Vertical DOP.
Definition: ros.h:172
uint8_t position_covariance_type
The method in which position_covariance_m2 was populated.
Definition: ros.h:229
double gdop
Geometric (position + time) DOP.
Definition: ros.h:169
double err_vert_m
Vertical position uncertainty (in meters) [epv].
Definition: ros.h:189
double err_speed_mps
Ground speed uncertainty (in meters/second) [eps].
Definition: ros.h:195
double err_dip_deg
Dip uncertainty (in degrees)
Definition: ros.h:210
double orientation[4]
The platform body orientation with respect to the local ENU frame, represented as a quaternion with t...
Definition: ros.h:260
double altitude_m
The WGS-84 altitude above the ellipsoid (in meters).
Definition: ros.h:105
Generic timestamp representation.
Definition: defs.h:95
double climb_mps
The vehicle vertical speed (in meters/second).
Definition: ros.h:127
static const uint8_t COVARIANCE_TYPE_DIAGONAL_KNOWN
Definition: ros.h:80
double roll_deg
The platform roll angle (in degrees).
Definition: ros.h:152
double err_3d_m
Spherical position uncertainty (in meters) [epe].
Definition: ros.h:183
double position_covariance_m2[9]
The 3x3 position covariance matrix (in m^2), resolved in the local ENU frame.
Definition: ros.h:223
double angular_velocity_rps[3]
Vehicle x/y/z rate of rotation (in radians/second), resolved in the body frame.
Definition: ros.h:271