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 so
18 // that floating point values are aligned on platforms that require it.
19 #pragma pack(push, 4)
20 
21 /**
22  * @defgroup enum_definitions Common Enumeration Definitions
23  * @{
24  */
25 
26 /**
27  * @brief System/constellation type definitions.
28  */
29 enum class SatelliteType : uint8_t {
30  UNKNOWN = 0,
31  GPS = 1,
32  GLONASS = 2,
33  LEO = 3,
34  GALILEO = 4,
35  BEIDOU = 5,
36  QZSS = 6,
37  MIXED = 7,
38  SBAS = 8,
39  IRNSS = 9
40 };
41 
42 /**
43  * @brief Navigation solution type definitions.
44  */
45 enum class SolutionType : uint8_t {
46  /** Invalid, no position available. */
47  Invalid = 0,
48  /** Autonomous GPS fix, no correction data used. */
49  AutonomousGPS = 1,
50  /** DGPS using a local base station or WAAS. */
51  DGPS = 2,
52  /** RTK fixed integers (one or more fixed). */
53  RTKFixed = 4,
54  /** RTK float integers. */
55  RTKFloat = 5,
56  /** Integrated position using dead reckoning. */
57  Integrate = 6,
58  /** Using vision measurements. */
59  Visual = 9,
60  /** Using PPP. */
61  PPP = 10,
62 };
63 
64 /**
65  * @brief Identifiers for the defined output message types.
66  * @ingroup messages
67  */
68 enum class MessageType : uint16_t {
69  INVALID = 0, ///< Invalid message type
70 
71  // INS solution messages.
72  POSE = 10000, ///< @ref PoseMessage
73  GNSS_INFO = 10001, ///< @ref GNSSInfoMessage
74  GNSS_SATELLITE = 10002, ///< @ref GNSSSatelliteMessage
75  POSE_AUX = 10003, ///< @ref PoseAuxMessage
76 
77  // Sensor measurement messages.
78  IMU_MEASUREMENT = 11000, ///< @ref IMUMeasurement
79 
80  // ROS messages.
81  ROS_POSE = 12000, ///< @ref ros::PoseMessage
82  ROS_GPS_FIX = 12010, ///< @ref ros::GPSFixMessage
83  ROS_IMU = 12011, ///< @ref ros::IMUMessage
84 };
85 
86 /** @} */
87 
88 /**
89  * @brief Generic timestamp representation.
90  *
91  * This structure may be used to store Point One system time values (referenced
92  * to the start of the device), UNIX times (referenced to January 1, 1970), or
93  * GPS times (referenced to January 6, 1980).
94  */
95 struct Timestamp {
96  static constexpr uint32_t INVALID = 0xFFFFFFFF;
97 
98  /**
99  * The number of full seconds since the epoch. Set to @ref INVALID if
100  * the timestamp is invalid or unknown.
101  */
102  uint32_t seconds = INVALID;
103 
104  /** The fractional part of the second, expressed in nanoseconds. */
105  uint32_t fraction_ns = INVALID;
106 };
107 
108 /**
109  * @brief The header present at the beginning of every message.
110  *
111  * The header is followed immediately in the binary stream by the message
112  * payload specified by @ref message_type.
113  */
115  static constexpr uint8_t SYNC0 = 0x2E; // '.'
116  static constexpr uint8_t SYNC1 = 0x31; // '1'
117 
118  static constexpr uint32_t INVALID_SOURCE_ID = 0xFFFFFFFF;
119 
120  /**
121  * The maximum expected message size (in bytes), used for sanity checking.
122  */
123  static const size_t MAX_MESSAGE_SIZE_BYTES = (1 << 24);
124 
125  /** Message sync bytes: always set to ASCII `.1` (0x2E, 0x31). */
126  uint8_t sync[2] = {SYNC0, SYNC1};
127 
128  uint8_t reserved[2] = {0};
129 
130  /**
131  * The 32-bit CRC of all bytes from and including the @ref protocol_version
132  * field to the last byte in the message, including the message payload. This
133  * uses the standard CRC-32 generator polynomial in reversed order
134  * (0xEDB88320).
135  *
136  * See also @ref crc_support.
137  */
138  uint32_t crc = 0;
139 
140  /** The version of the P1 binary protocol being used. */
141  uint8_t protocol_version = 2;
142 
143  uint8_t reserved_1 = 0;
144 
145  /** Type identifier for the serialized message to follow. */
147 
148  /** The sequence number of this message. */
149  uint32_t sequence_number = 0;
150 
151  /** The size of the serialized message (bytes). */
152  uint32_t payload_size_bytes = 0;
153 
154  /** Identifies the source of the serialized data. */
156 };
157 
158 #pragma pack(pop)
159 
160 /**
161  * @brief Get a human-friendly string name for the specified @ref SatelliteType
162  * (GNSS constellation).
163  * @ingroup enum_definitions
164  *
165  * @param type The desired satellite type.
166  *
167  * @return The corresponding string name.
168  */
169 inline std::string to_string(SatelliteType type) {
170  switch (type) {
172  return "Unknown";
173 
174  case SatelliteType::GPS:
175  return "GPS";
176 
178  return "GLONASS";
179 
180  case SatelliteType::LEO:
181  return "LEO";
182 
184  return "Galileo";
185 
187  return "BeiDou";
188 
189  case SatelliteType::QZSS:
190  return "QZSS";
191 
193  return "Mixed";
194 
195  case SatelliteType::SBAS:
196  return "SBAS";
197 
199  return "IRNSS";
200 
201  default:
202  return "Invalid System (" + std::to_string((int)type) + ")";
203  }
204 }
205 
206 /**
207  * @brief @ref SatelliteType stream operator.
208  * @ingroup enum_definitions
209  */
210 inline std::ostream& operator<<(std::ostream& stream, SatelliteType type) {
211  return (stream << to_string(type));
212 }
213 
214 /**
215  * @brief Get a human-friendly string name for the specified @ref MessageType.
216  * @ingroup enum_definitions
217  *
218  * @param type The desired message type.
219  *
220  * @return The corresponding string name.
221  */
222 inline std::string to_string(MessageType type) {
223  switch (type) {
225  return "Invalid";
226 
227  case MessageType::POSE:
228  return "Pose";
229 
231  return "GNSS Info";
232 
234  return "GNSS Satellite";
235 
237  return "Pose Auxiliary";
238 
240  return "IMU Measurement";
241 
243  return "ROS Pose";
244 
246  return "ROS GPSFix";
247 
249  return "ROS IMU";
250 
251  default:
252  return "Unrecognized Message (" + std::to_string((int)type) + ")";
253  }
254 }
255 
256 /**
257  * @brief @ref MessageType stream operator.
258  * @ingroup enum_definitions
259  */
260 inline std::ostream& operator<<(std::ostream& stream, MessageType type) {
261  return (stream << to_string(type));
262 }
263 
264 /**
265  * @brief Get a human-friendly string name for the specified @ref SolutionType.
266  * @ingroup enum_definitions
267  *
268  * @param type The desired message type.
269  *
270  * @return The corresponding string name.
271  */
272 inline std::string to_string(SolutionType type) {
273  switch (type) {
275  return "Invalid";
276 
278  return "Stand Alone GNSS";
279 
280  case SolutionType::DGPS:
281  return "Differential GNSS";
282 
284  return "Fixed RTK GNSS";
285 
287  return "Real-valued Ambiguity RTK GNSS";
288 
290  return "Dead Reckoning";
291 
293  return "Visual Navigation";
294 
295  case SolutionType::PPP:
296  return "PPP GNSS";
297 
298  default:
299  return "Unrecognized Solution Type (" + std::to_string((int)type) + ")";
300  }
301 }
302 
303 /**
304  * @brief @ref SolutionType stream operator.
305  * @ingroup enum_definitions
306  */
307 inline std::ostream& operator<<(std::ostream& stream, SolutionType type) {
308  return (stream << to_string(type));
309 }
310 
311 /**
312  * @defgroup messages Message Definitions
313  * @brief Type definitions for all defined messages.
314  *
315  * See also @ref MessageType.
316  */
317 
318 } // namespace messages
319 } // namespace fusion_engine
320 } // namespace point_one
uint32_t source_identifier
Identifies the source of the serialized data.
Definition: defs.h:155
@ POSE_AUX
PoseAuxMessage
static constexpr uint8_t SYNC0
Definition: defs.h:115
MessageType
Identifiers for the defined output message types.
Definition: defs.h:68
uint32_t sequence_number
The sequence number of this message.
Definition: defs.h:149
@ RTKFloat
RTK float integers.
SolutionType
Navigation solution type definitions.
Definition: defs.h:45
MessageType message_type
Type identifier for the serialized message to follow.
Definition: defs.h:146
The header present at the beginning of every message.
Definition: defs.h:114
static const size_t MAX_MESSAGE_SIZE_BYTES
The maximum expected message size (in bytes), used for sanity checking.
Definition: defs.h:123
@ GNSS_INFO
GNSSInfoMessage
@ MIXED
std::string to_string(SolutionType type)
Get a human-friendly string name for the specified SolutionType.
Definition: defs.h:272
@ BEIDOU
uint8_t sync[2]
Message sync bytes: always set to ASCII .1 (0x2E, 0x31).
Definition: defs.h:126
@ ROS_GPS_FIX
ros::GPSFixMessage
@ ROS_POSE
ros::PoseMessage
@ INVALID
Invalid message type.
@ SBAS
@ UNKNOWN
@ DGPS
DGPS using a local base station or WAAS.
@ GNSS_SATELLITE
GNSSSatelliteMessage
@ AutonomousGPS
Autonomous GPS fix, no correction data used.
SatelliteType
System/constellation type definitions.
Definition: defs.h:29
@ IMU_MEASUREMENT
IMUMeasurement
@ RTKFixed
RTK fixed integers (one or more fixed).
std::ostream & operator<<(std::ostream &stream, SatelliteType type)
SatelliteType stream operator.
Definition: defs.h:210
static constexpr uint32_t INVALID_SOURCE_ID
Definition: defs.h:118
uint8_t protocol_version
The version of the P1 binary protocol being used.
Definition: defs.h:141
@ ROS_IMU
ros::IMUMessage
@ POSE
PoseMessage
@ Invalid
Invalid, no position available.
Definition: crc.cc:49
@ Integrate
Integrated position using dead reckoning.
static constexpr uint8_t SYNC1
Definition: defs.h:116
@ Visual
Using vision measurements.
static constexpr uint32_t INVALID
Definition: defs.h:96
@ GPS
uint32_t payload_size_bytes
The size of the serialized message (bytes).
Definition: defs.h:152
std::string to_string(SatelliteType type)
Get a human-friendly string name for the specified SatelliteType (GNSS constellation).
Definition: defs.h:169
uint32_t seconds
The number of full seconds since the epoch.
Definition: defs.h:102
uint32_t fraction_ns
The fractional part of the second, expressed in nanoseconds.
Definition: defs.h:105
@ GLONASS
Generic timestamp representation.
Definition: defs.h:95
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:138
@ PPP
Using PPP.
@ QZSS
@ LEO
@ GALILEO
@ IRNSS