defs.h
Go to the documentation of this file.
1 /**************************************************************************/ /**
2  * @brief Point One FusionEngine output message common definitions.
3  * @file
4  ******************************************************************************/
5 
6 #pragma once
7 
8 #include <cmath> // For NAN
9 #include <cstdint>
10 #include <ostream>
11 #include <string>
12 
13 namespace point_one {
14 namespace fusion_engine {
15 namespace messages {
16 
17 // Enforce 4-byte alignment and packing of all data structures and values.
18 // Floating point values are aligned on platforms that require it. This is done
19 // with a combination of setting struct attributes, and manual alignment
20 // within the definitions. See the "Message Packing" section of the README.
21 #pragma pack(push, 1)
22 
23 /**
24  * @defgroup enum_definitions Common Enumeration Definitions
25  * @{
26  */
27 
28 /**
29  * @brief System/constellation type definitions.
30  */
31 enum class SatelliteType : uint8_t {
32  UNKNOWN = 0,
33  GPS = 1,
34  GLONASS = 2,
35  LEO = 3,
36  GALILEO = 4,
37  BEIDOU = 5,
38  QZSS = 6,
39  MIXED = 7,
40  SBAS = 8,
41  IRNSS = 9,
42  MAX_VALUE = IRNSS,
43 };
44 
45 /**
46  * @brief Navigation solution type definitions.
47  */
48 enum class SolutionType : uint8_t {
49  /** Invalid, no position available. */
50  Invalid = 0,
51  /** Standalone GNSS fix, no correction data used. */
52  AutonomousGPS = 1,
53  /**
54  * Differential GNSS pseudorange solution using a local RTK base station or
55  * SSR or SBAS corrections.
56  */
57  DGPS = 2,
58  /**
59  * GNSS RTK solution with fixed integer carrier phase ambiguities (one or more
60  * signals fixed).
61  */
62  RTKFixed = 4,
63  /** GNSS RTK solution with floating point carrier phase ambiguities. */
64  RTKFloat = 5,
65  /** Integrated position using dead reckoning. */
66  Integrate = 6,
67  /** Using vision measurements. */
68  Visual = 9,
69  /**
70  * GNSS precise point positioning (PPP) pseudorange/carrier phase solution.
71  */
72  PPP = 10,
73  MAX_VALUE = PPP,
74 };
75 
76 /**
77  * @brief Identifiers for the defined output message types.
78  * @ingroup messages
79  */
80 enum class MessageType : uint16_t {
81  INVALID = 0, ///< Invalid message type
82 
83  // Navigation solution messages.
84  POSE = 10000, ///< @ref PoseMessage
85  GNSS_INFO = 10001, ///< @ref GNSSInfoMessage
86  GNSS_SATELLITE = 10002, ///< @ref GNSSSatelliteMessage
87  POSE_AUX = 10003, ///< @ref PoseAuxMessage
88 
89  // Sensor measurement messages.
90  IMU_MEASUREMENT = 11000, ///< @ref IMUMeasurement
91 
92  // ROS messages.
93  ROS_POSE = 12000, ///< @ref ros::PoseMessage
94  ROS_GPS_FIX = 12010, ///< @ref ros::GPSFixMessage
95  ROS_IMU = 12011, ///< @ref ros::IMUMessage
96 
97  // Command and control messages.
98  COMMAND_RESPONSE = 13000, ///< @ref CommandResponseMessage
99  MESSAGE_REQUEST = 13001, ///< @ref MessageRequest
100  RESET_REQUEST = 13002, ///< @ref ResetRequest
101  VERSION_INFO = 13003, ///< @ref VersionInfoMessage
102  EVENT_NOTIFICATION = 13004, ///< @ref EventNotificationMessage
103 
104  SET_CONFIG = 13100, ///< @ref SetConfigMessage
105  GET_CONFIG = 13101, ///< @ref GetConfigMessage
106  SAVE_CONFIG = 13102, ///< @ref SaveConfigMessage
107  CONFIG_DATA = 13103, ///< @ref ConfigDataMessage
108 
109  MAX_VALUE = CONFIG_DATA, ///< The maximum defined @ref MessageType enum value.
110 };
111 
112 /** @} */
113 
114 /**
115  * @brief Generic timestamp representation.
116  *
117  * This structure may be used to store Point One system time values (referenced
118  * to the start of the device), UNIX times (referenced to January 1, 1970), or
119  * GPS times (referenced to January 6, 1980).
120  */
121 struct alignas(4) Timestamp {
122  static constexpr uint32_t INVALID = 0xFFFFFFFF;
123 
124  /**
125  * The number of full seconds since the epoch. Set to @ref INVALID if
126  * the timestamp is invalid or unknown.
127  */
128  uint32_t seconds = INVALID;
129 
130  /** The fractional part of the second, expressed in nanoseconds. */
131  uint32_t fraction_ns = INVALID;
132 };
133 
134 /**
135  * @brief The header present at the beginning of every message.
136  * @ingroup messages
137  *
138  * The header is followed immediately in the binary stream by the message
139  * payload specified by @ref message_type.
140  */
141 struct alignas(4) MessageHeader {
142  static constexpr uint8_t SYNC0 = 0x2E; // '.'
143  static constexpr uint8_t SYNC1 = 0x31; // '1'
144 
145  static constexpr uint32_t INVALID_SOURCE_ID = 0xFFFFFFFF;
146 
147  /**
148  * The maximum expected message size (in bytes), used for sanity checking.
149  */
150  static const size_t MAX_MESSAGE_SIZE_BYTES = (1 << 24);
151 
152  /** Message sync bytes: always set to ASCII `.1` (0x2E, 0x31). */
153  uint8_t sync[2] = {SYNC0, SYNC1};
154 
155  uint8_t reserved[2] = {0};
156 
157  /**
158  * The 32-bit CRC of all bytes from and including the @ref protocol_version
159  * field to the last byte in the message, including the message payload. This
160  * uses the standard CRC-32 generator polynomial in reversed order
161  * (0xEDB88320).
162  *
163  * See also @ref crc_support.
164  */
165  uint32_t crc = 0;
166 
167  /** The version of the P1 binary protocol being used. */
168  uint8_t protocol_version = 2;
169 
170  /**
171  * The version of the message type specified by @ref message_type to follow.
172  */
173  uint8_t message_version = 0;
174 
175  /** Type identifier for the serialized message to follow. */
177 
178  /** The sequence number of this message. */
179  uint32_t sequence_number = 0;
180 
181  /** The size of the serialized message (bytes). */
182  uint32_t payload_size_bytes = 0;
183 
184  /** Identifies the source of the serialized data. */
186 };
187 
188 /**
189  * @brief The base class for all message payloads.
190  * @ingroup messages
191  */
193  // Currently empty - used simply to distinguish between payload definitions
194  // and other types.
195 };
196 
197 #pragma pack(pop)
198 
199 /**
200  * @brief Get a human-friendly string name for the specified @ref SatelliteType
201  * (GNSS constellation).
202  * @ingroup enum_definitions
203  *
204  * @param type The desired satellite type.
205  *
206  * @return The corresponding string name.
207  */
208 inline const char* to_string(SatelliteType type) {
209  switch (type) {
211  return "Unknown";
212 
213  case SatelliteType::GPS:
214  return "GPS";
215 
217  return "GLONASS";
218 
219  case SatelliteType::LEO:
220  return "LEO";
221 
223  return "Galileo";
224 
226  return "BeiDou";
227 
228  case SatelliteType::QZSS:
229  return "QZSS";
230 
232  return "Mixed";
233 
234  case SatelliteType::SBAS:
235  return "SBAS";
236 
238  return "IRNSS";
239 
240  default:
241  return "Invalid System";
242  }
243 }
244 
245 /**
246  * @brief @ref SatelliteType stream operator.
247  * @ingroup enum_definitions
248  */
249 inline std::ostream& operator<<(std::ostream& stream, SatelliteType type) {
250  stream << to_string(type) << " (" << (int)type << ")";
251  return stream;
252 }
253 
254 /**
255  * @brief Get a human-friendly string name for the specified @ref MessageType.
256  * @ingroup enum_definitions
257  *
258  * @param type The desired message type.
259  *
260  * @return The corresponding string name.
261  */
262 inline const char* to_string(MessageType type) {
263  switch (type) {
265  return "Invalid";
266 
267  // Navigation solution messages.
268  case MessageType::POSE:
269  return "Pose";
270 
272  return "GNSS Info";
273 
275  return "GNSS Satellite";
276 
278  return "Pose Auxiliary";
279 
280  // Sensor measurement messages.
282  return "IMU Measurement";
283 
284  // ROS messages.
286  return "ROS Pose";
287 
289  return "ROS GPSFix";
290 
292  return "ROS IMU";
293 
294  // Command and control messages.
296  return "Command Response";
297 
299  return "Message Transmission Request";
300 
302  return "Reset Request";
303 
305  return "Version Information";
306 
308  return "Event Notification";
309 
311  return "Set Configuration Parameter";
312 
314  return "Get Configuration Parameter";
315 
317  return "Save Configuration";
318 
320  return "Configuration Parameter Value";
321 
322  default:
323  return "Unrecognized Message";
324  }
325 }
326 
327 /**
328  * @brief @ref MessageType stream operator.
329  * @ingroup enum_definitions
330  */
331 inline std::ostream& operator<<(std::ostream& stream, MessageType type) {
332  stream << to_string(type) << " (" << (int)type << ")";
333  return stream;
334 }
335 
336 /**
337  * @brief Get a human-friendly string name for the specified @ref SolutionType.
338  * @ingroup enum_definitions
339  *
340  * @param type The desired message type.
341  *
342  * @return The corresponding string name.
343  */
344 inline const char* to_string(SolutionType type) {
345  switch (type) {
347  return "Invalid";
348 
350  return "Stand Alone GNSS";
351 
352  case SolutionType::DGPS:
353  return "Differential GNSS";
354 
356  return "Fixed RTK GNSS";
357 
359  return "Real-valued Ambiguity RTK GNSS";
360 
362  return "Dead Reckoning";
363 
365  return "Visual Navigation";
366 
367  case SolutionType::PPP:
368  return "PPP GNSS";
369 
370  default:
371  return "Unrecognized Solution Type";
372  }
373 }
374 
375 /**
376  * @brief @ref SolutionType stream operator.
377  * @ingroup enum_definitions
378  */
379 inline std::ostream& operator<<(std::ostream& stream, SolutionType type) {
380  stream << to_string(type) << " (" << (int)type << ")";
381  return stream;
382 }
383 
384 /**
385  * @defgroup messages Message Definitions
386  * @brief Type definitions for all defined messages.
387  *
388  * See also @ref MessageType.
389  */
390 
391 } // namespace messages
392 } // namespace fusion_engine
393 } // namespace point_one
uint32_t source_identifier
Identifies the source of the serialized data.
Definition: defs.h:185
@ MAX_VALUE
The maximum defined MessageType enum value.
@ POSE_AUX
PoseAuxMessage
static constexpr uint8_t SYNC0
Definition: defs.h:142
MessageType
Identifiers for the defined output message types.
Definition: defs.h:80
uint32_t sequence_number
The sequence number of this message.
Definition: defs.h:179
@ RTKFloat
GNSS RTK solution with floating point carrier phase ambiguities.
SolutionType
Navigation solution type definitions.
Definition: defs.h:48
MessageType message_type
Type identifier for the serialized message to follow.
Definition: defs.h:176
The header present at the beginning of every message.
Definition: defs.h:141
@ COMMAND_RESPONSE
CommandResponseMessage
static const size_t MAX_MESSAGE_SIZE_BYTES
The maximum expected message size (in bytes), used for sanity checking.
Definition: defs.h:150
@ GNSS_INFO
GNSSInfoMessage
@ MIXED
@ CONFIG_DATA
ConfigDataMessage
@ BEIDOU
uint8_t sync[2]
Message sync bytes: always set to ASCII .1 (0x2E, 0x31).
Definition: defs.h:153
@ ROS_GPS_FIX
ros::GPSFixMessage
@ ROS_POSE
ros::PoseMessage
@ INVALID
Invalid message type.
@ MAX_VALUE
@ SBAS
@ UNKNOWN
@ DGPS
Differential GNSS pseudorange solution using a local RTK base station or SSR or SBAS corrections.
@ SAVE_CONFIG
SaveConfigMessage
@ GNSS_SATELLITE
GNSSSatelliteMessage
@ AutonomousGPS
Standalone GNSS fix, no correction data used.
SatelliteType
System/constellation type definitions.
Definition: defs.h:31
@ MAX_VALUE
The base class for all message payloads.
Definition: defs.h:192
@ IMU_MEASUREMENT
IMUMeasurement
@ RESET_REQUEST
ResetRequest
@ RTKFixed
GNSS RTK solution with fixed integer carrier phase ambiguities (one or more signals fixed).
static constexpr uint32_t INVALID_SOURCE_ID
Definition: defs.h:145
@ VERSION_INFO
VersionInfoMessage
uint8_t protocol_version
The version of the P1 binary protocol being used.
Definition: defs.h:168
@ ROS_IMU
ros::IMUMessage
@ POSE
PoseMessage
@ Invalid
Invalid, no position available.
Definition: configuration.h:21
@ Integrate
Integrated position using dead reckoning.
static constexpr uint8_t SYNC1
Definition: defs.h:143
@ Visual
Using vision measurements.
static constexpr uint32_t INVALID
Definition: defs.h:122
@ GPS
uint32_t payload_size_bytes
The size of the serialized message (bytes).
Definition: defs.h:182
uint32_t seconds
The number of full seconds since the epoch.
Definition: defs.h:128
uint32_t fraction_ns
The fractional part of the second, expressed in nanoseconds.
Definition: defs.h:131
@ GET_CONFIG
GetConfigMessage
@ SET_CONFIG
SetConfigMessage
std::ostream & operator<<(std::ostream &stream, ConfigType type)
ConfigType stream operator.
@ GLONASS
@ EVENT_NOTIFICATION
EventNotificationMessage
Generic timestamp representation.
Definition: defs.h:121
uint32_t crc
The 32-bit CRC of all bytes from and including the protocol_version field to the last byte in the mes...
Definition: defs.h:165
const char * to_string(ConfigType type)
Get a human-friendly string name for the specified ConfigType.
Definition: configuration.h:94
@ PPP
GNSS precise point positioning (PPP) pseudorange/carrier phase solution.
@ QZSS
@ MESSAGE_REQUEST
MessageRequest
uint8_t message_version
The version of the message type specified by message_type to follow.
Definition: defs.h:173
@ LEO
@ GALILEO
@ IRNSS