solution.h
Go to the documentation of this file.
1 /**************************************************************************/ /**
2  * @brief Platform position/attitude solution messages.
3  * @file
4  ******************************************************************************/
5 
6 #pragma once
7 
10 
11 namespace point_one {
12 namespace fusion_engine {
13 namespace messages {
14 
15 // Enforce 4-byte alignment and packing of all data structures and values.
16 // Floating point values are aligned on platforms that require it. This is done
17 // with a combination of setting struct attributes, and manual alignment
18 // within the definitions. See the "Message Packing" section of the README.
19 #pragma pack(push, 1)
20 
21 /**
22  * @defgroup solution_messages Navigation Solution Message Definitions
23  * @brief Output messages containing position, navigation, and time results.
24  * @ingroup messages
25  *
26  * See also @ref messages.
27  */
28 
29 /**
30  * @brief Platform pose solution: position, velocity, attitude (@ref
31  * MessageType::POSE, version 1.1).
32  * @ingroup solution_messages
33  *
34  * @note
35  * All data is timestamped using the Point One Time, which is a monotonic
36  * timestamp referenced to the start of the device. Corresponding messages (@ref
37  * GNSSInfoMessage, @ref GNSSSatelliteMessage, etc.) may be associated using
38  * their @ref p1_time values.
39  */
41  static constexpr MessageType MESSAGE_TYPE = MessageType::POSE;
42  static constexpr uint8_t MESSAGE_VERSION = 1;
43  static constexpr int16_t INVALID_UNDULATION = INT16_MIN;
44 
45  /** The time of the message, in P1 time (beginning at power-on). */
47 
48  /** The GPS time of the message, if available, referenced to 1980/1/6. */
50 
51  /** The type of this position solution. */
53 
54  uint8_t reserved = 0;
55 
56  /**
57  * The geoid undulation at at the current location (i.e., the difference
58  * between the WGS-84 ellipsoid and the geoid).
59  *
60  * Height above the ellipsoid can be converted to a corresponding height above
61  * the geoid (orthometric height or height above mean sea level (MSL)) as
62  * follows:
63  *
64  * @f[
65  * h_{orthometric} = h_{ellipsoid} - undulation
66  * @f]
67  *
68  * Stored in units of 0.01 meters: `undulation_m = undulation_cm * 0.01`. Set
69  * to `-32768` if invalid.
70  *
71  * Added in @ref PoseMessage version 1.1.
72  */
73  int16_t undulation_cm = INVALID_UNDULATION;
74 
75  /**
76  * The geodetic latitude, longitude, and altitude (in degrees/degrees/meters),
77  * expressed using the WGS-84 reference ellipsoid.
78  *
79  * @section p1_fe_pose_datum Datum/Epoch Considerations
80  * When comparing two positions, it is very important to make sure they are
81  * compared using the same geodetic datum, defined at the same time (epoch).
82  * Failing to do so can cause very large unexpected differences since the
83  * ground moves in various directions over time due to motion of tectonic
84  * plates.
85  *
86  * For example, the coordinates for a point on the ground in San Francisco
87  * expressed in the ITRF14 datum may differ by multiple meters from the
88  * coordinates for the same point expressed the NAD83 datum. Similarly, the
89  * coordinates for that location expressed in the ITRF14 2017.0 epoch
90  * (January 1, 2017) may differ by 12 cm or more when expressed using the
91  * ITRF14 2021.0 epoch (January 1, 2021).
92  *
93  * The datum and epoch to which the position reported in this message is
94  * aligned depends on the current @ref solution_type.
95  * - @ref SolutionType::AutonomousGPS / @ref SolutionType::DGPS /
96  * @ref SolutionType::PPP - Standalone solutions (i.e., no differential
97  * corrections) are aligned to the WGS-84 datum as broadcast live by GPS
98  * (aligns closely with the ITRF08/14 datums).
99  * - @ref SolutionType::RTKFloat / @ref SolutionType::RTKFixed - When
100  * differential corrections are applied, the reference datum and epoch are
101  * defined by the corrections provider. Point One's Polaris Corrections
102  * Service produces corrections using the ITRF14 datum. See
103  * https://pointonenav.com/polaris for more details.
104  * - @ref SolutionType::Integrate - When the INS is dead reckoning in the
105  * absence of GNSS, vision, or other measurements anchored in absolute world
106  * coordinates, the position solution is defined in the same datum/epoch
107  * specified by the previous solution type (e.g., WGS-84 if previously
108  * standalone GNSS, i.e., @ref SolutionType::AutonomousGPS).
109  */
110  double lla_deg[3] = {NAN, NAN, NAN};
111 
112  /**
113  * The position standard deviation (in meters), resolved with respect to the
114  * local ENU tangent plane: east, north, up.
115  */
116  float position_std_enu_m[3] = {NAN, NAN, NAN};
117 
118  /**
119  * The platform attitude (in degrees), if known, described as intrinsic
120  * Euler-321 angles (yaw, pitch, roll) with respect to the local ENU tangent
121  * plane. Set to `NAN` if attitude is not available.
122  *
123  * @note
124  * The platform body axes are defined as +x forward, +y left, and +z up. A
125  * positive yaw is a left turn, positive pitch points the nose of the vehicle
126  * down, and positive roll is a roll toward the right. Yaw is measured from
127  * east in a counter-clockwise direction. For example, north is +90 degrees
128  * (i.e., `heading = 90.0 - ypr_deg[0]`).
129  */
130  double ypr_deg[3] = {NAN, NAN, NAN};
131 
132  /**
133  * The attitude standard deviation (in degrees): yaw, pitch, roll.
134  */
135  float ypr_std_deg[3] = {NAN, NAN, NAN};
136 
137  /**
138  * The platform velocity (in meters/second), resolved in the body frame. Set
139  * to `NAN` if attitude is not available for the body frame transformation.
140  */
141  double velocity_body_mps[3] = {NAN, NAN, NAN};
142 
143  /**
144  * The velocity standard deviation (in meters/second), resolved in the body
145  * frame.
146  */
147  float velocity_std_body_mps[3] = {NAN, NAN, NAN};
148 
149  /** The estimated aggregate 3D protection level (in meters). */
150  float aggregate_protection_level_m = NAN;
151  /** The estimated 2D horizontal protection level (in meters). */
152  float horizontal_protection_level_m = NAN;
153  /** The estimated vertical protection level (in meters). */
154  float vertical_protection_level_m = NAN;
155 };
156 
157 /**
158  * @brief Auxiliary platform pose information (@ref MessageType::POSE_AUX,
159  * version 1.0).
160  * @ingroup solution_messages
161  */
163  static constexpr MessageType MESSAGE_TYPE = MessageType::POSE_AUX;
164  static constexpr uint8_t MESSAGE_VERSION = 0;
165 
166  /** The time of the message, in P1 time (beginning at power-on). */
168 
169  /**
170  * The position standard deviation (in meters), resolved in the body frame.
171  * Set to `NAN` if attitude is not available for the body frame
172  * transformation.
173  */
174  float position_std_body_m[3] = {NAN, NAN, NAN};
175 
176  /**
177  * The 3x3 position covariance matrix (in m^2), resolved in the local ENU
178  * frame. Values are stored in row-major order.
179  */
180  double position_cov_enu_m2[9] = {NAN};
181 
182  /**
183  * The platform body orientation with respect to the local ENU frame,
184  * represented as a quaternion with the scalar component last (x, y, z, w).
185  */
186  double attitude_quaternion[4] = {NAN, NAN, NAN, NAN};
187 
188  /**
189  * The platform velocity (in meters/second), resolved in the local ENU frame.
190  */
191  double velocity_enu_mps[3] = {NAN, NAN, NAN};
192 
193  /**
194  * The velocity standard deviation (in meters/second), resolved in the local
195  * ENU frame.
196  */
197  float velocity_std_enu_mps[3] = {NAN, NAN, NAN};
198 };
199 
200 /**
201  * @brief Information about the GNSS data used in the @ref PoseMessage with the
202  * corresponding timestamp (@ref MessageType::GNSS_INFO, version 1.1).
203  * @ingroup solution_messages
204  *
205  * @note
206  * The deprecated `last_differential_time` field was removed in version 1.1 of
207  * this message, and was replaced by the new @ref leap_second, @ref num_svs,
208  * @ref corrections_age, and @ref baseline_distance fields. Attempting to use
209  * those fields on version 0 messages will result in undefined behavior.
210  */
212  static constexpr MessageType MESSAGE_TYPE = MessageType::GNSS_INFO;
213  static constexpr uint8_t MESSAGE_VERSION = 1;
214 
215  static constexpr uint16_t INVALID_LEAP_SECOND = 0xFF;
216  static constexpr uint16_t INVALID_AGE = 0xFFFF;
217  static constexpr uint16_t INVALID_DISTANCE = 0xFFFF;
218  static constexpr uint32_t INVALID_REFERENCE_STATION = 0xFFFFFFFF;
219 
220  /** The time of the message, in P1 time (beginning at power-on). */
222 
223  /** The GPS time of the message, if available, referenced to 1980/1/6. */
225 
226  /**
227  * The current UTC leap second (offset between UTC and GPS time), if known.
228  * Set to 0xFF if invalid.
229  *
230  * Added in message version 1.
231  */
232  uint8_t leap_second = INVALID_LEAP_SECOND;
233 
234  /** The number of satellites used in the current position solution. */
235  uint8_t num_svs = 0;
236 
237  uint8_t reserved[2];
238 
239  /**
240  * The age of the most recently received GNSS corrections data (in 0.1
241  * seconds). Set to 0xFFFF if invalid.
242  *
243  * Added in message version 1.
244  */
245  uint16_t corrections_age = INVALID_AGE;
246 
247  /**
248  * The distance between the device and the GNSS corrections base station.
249  * Stored in units of 10 meters:
250  * `baseline_distance_m = baseline_distance * 10`. Set to 0xFFFF if invalid.
251  *
252  * Added in message version 1.
253  */
254  uint16_t baseline_distance = INVALID_DISTANCE;
255 
256  /**
257  * The ID of the GNSS corrections base station, if used. Set to 0xFFFFFFFF if
258  * invalid.
259  */
260  uint32_t reference_station_id = INVALID_REFERENCE_STATION;
261 
262  /** The geometric dilution of precision (GDOP). */
263  float gdop = NAN;
264  /** The position dilution of precision (PDOP). */
265  float pdop = NAN;
266  /** The horizontal dilution of precision (HDOP). */
267  float hdop = NAN;
268  /** The vertical dilution of precision (VDOP). */
269  float vdop = NAN;
270 
271  /** GPS time alignment standard deviation (in seconds). */
272  float gps_time_std_sec = NAN;
273 };
274 
275 /**
276  * @brief Information about the individual satellites used in the @ref
277  * PoseMessage and @ref GNSSInfoMessage with the corresponding timestamp
278  * (@ref MessageType::GNSS_SATELLITE, version 1.0).
279  * @ingroup solution_messages
280  *
281  * This message is followed by `N` @ref SatelliteInfo objects, where `N` is
282  * equal to @ref num_satellites. For example, a message with two satellites
283  * would be serialized as:
284  *
285  * ```
286  * {MessageHeader, GNSSSatelliteMessage, SatelliteInfo, SatelliteInfo, ...}
287  * ```
288  */
290  static constexpr MessageType MESSAGE_TYPE = MessageType::GNSS_SATELLITE;
291  static constexpr uint8_t MESSAGE_VERSION = 0;
292 
293  /** The time of the message, in P1 time (beginning at power-on). */
295 
296  /** The GPS time of the message, if available, referenced to 1980/1/6. */
298 
299  /** The number of known satellites. */
300  uint16_t num_satellites = 0;
301 
302  uint8_t reserved[2] = {0};
303 };
304 
305 /**
306  * @brief Information about an individual satellite (see @ref
307  * GNSSSatelliteMessage).
308  *
309  * For satellites where @ref usage is 0, the satellite may either be currently
310  * tracked by the receiver but not used for navigation, or may just be expected
311  * according to available ephemeris data.
312  */
314  /**
315  * @defgroup satellite_usage Bit definitions for the satellite usage bitmask
316  * (@ref SatelliteInfo::usage).
317  * @{
318  */
319  static constexpr uint8_t SATELLITE_USED = 0x01;
320  /** @} */
321 
322  static constexpr int16_t INVALID_CN0 = 0;
323 
324  /** The GNSS system to which this satellite belongs. */
326 
327  /** The satellite's PRN (or slot number for GLONASS). */
328  uint8_t prn = 0;
329 
330  /**
331  * A bitmask specifying how this satellite was used in the position solution.
332  * Set to 0 if the satellite was not used. See @ref satellite_usage.
333  */
334  uint8_t usage = 0;
335 
336  /**
337  * The carrier-to-noise density ratio (C/N0) for the L1 signal on the
338  * satellite.
339  *
340  * Stored in units of 0.25 dB-Hz: `cn0_dbhz = cn0 * 0.25`. Set to 0 if
341  * invalid. The range of this field is 0.25-63.75 dB-Hz. Values outside of
342  * this range will be clipped to the min/max values.
343  *
344  * @note
345  * If the satellite is not tracking L1 (or the L1-equivalent for other
346  * constellations, e.g., G1 for GLONASS) but another frequency is being used,
347  * that signal's C/N0 value will be reported.
348  *
349  * Added in @ref GNSSSatelliteMessage version 1.1.
350  */
351  uint8_t cn0 = INVALID_CN0;
352 
353  /** The azimuth of the satellite (in degrees). */
354  float azimuth_deg = NAN;
355 
356  /** The elevation of the satellite (in degrees). */
357  float elevation_deg = NAN;
358 };
359 
360 /**
361  * @brief The stages of the device calibration process.
362  * @ingroup solution_messages
363  */
364 enum class CalibrationStage : uint8_t {
365  UNKNOWN = 0, ///< Calibration stage not known.
366  MOUNTING_ANGLE = 1, ///< Estimating IMU mounting angles.
367  DONE = 255, ///< Calibration complete.
368 };
369 
370 /**
371  * @brief Get a human-friendly string name for the specified @ref
372  * CalibrationStage.
373  *
374  * @param val The enum to get the string name for.
375  *
376  * @return The corresponding string name.
377  */
379  switch (val) {
381  return "Unknown";
383  return "IMU Mounting Angles";
385  return "Done";
386  default:
387  return "Unrecognized";
388  }
389 }
390 
391 /**
392  * @brief @ref CalibrationStage stream operator.
393  */
395  stream << to_string(val) << " (" << (int)val << ")";
396  return stream;
397 }
398 
399 /**
400  * @brief Device calibration status update. (@ref
401  * MessageType::CALIBRATION_STATUS, version 1.1).
402  * @brief
403  * @ingroup solution_messages
404  */
406  static constexpr MessageType MESSAGE_TYPE = MessageType::CALIBRATION_STATUS;
407  static constexpr uint8_t MESSAGE_VERSION = 1;
408 
409  /** The most recent P1 time, if available. */
411 
412  /**
413  * @name Calibration State Data
414  * @{
415  */
416 
417  /** The current calibration stage. */
419 
420  uint8_t reserved1[3] = {0};
421 
422  /** The IMU yaw, pitch, and roll mounting angle offsets (in degrees). */
423  float ypr_deg[3] = {NAN, NAN, NAN};
424 
425  /**
426  * The IMU yaw, pitch, and roll mounting angle standard deviations (in
427  * degrees).
428  */
429  float ypr_std_dev_deg[3] = {NAN, NAN, NAN};
430 
431  /** The accumulated calibration travel distance (in meters). */
432  float travel_distance_m = 0.0;
433 
434  uint8_t reserved2[24] = {0};
435 
436  /** @} */
437 
438  /**
439  * @name Calibration Process Status
440  * @{
441  */
442 
443  /**
444  * Set to 1 once the navigation engine state is validated after
445  * initialization.
446  */
447  uint8_t state_verified{0};
448 
449  uint8_t reserved3[3] = {0};
450 
451  /**
452  * The completion percentage for gyro bias estimation, stored with a
453  * scale factor of 0.5% (0-200).
454  */
455  uint8_t gyro_bias_percent_complete = 0;
456 
457  /**
458  * The completion percentage for accelerometer bias estimation, stored with a
459  * scale factor of 0.5% (0-200).
460  */
461  uint8_t accel_bias_percent_complete = 0;
462 
463  /**
464  * The completion percentage for IMU mounting angle estimation, stored with a
465  * scale factor of 0.5% (0-200).
466  */
467  uint8_t mounting_angle_percent_complete = 0;
468 
469  uint8_t reserved4[5] = {0};
470 
471  /** @} */
472 
473  /**
474  * @name Calibration Thresholds
475  * @{
476  */
477 
478  /**
479  * The minimum accumulated calibration travel distance needed to complete
480  * mounting angle calibration.
481  */
482  float min_travel_distance_m = NAN;
483 
484  /**
485  * The max threshold for each of the YPR mounting angle states (in degrees),
486  * above which calibration is incomplete.
487  */
488  float mounting_angle_max_std_dev_deg[3] = {NAN, NAN, NAN};
489 
490  /** @} */
491 };
492 
493 /**
494  * @brief Relative ENU position to base station (@ref
495  * MessageType::RELATIVE_ENU_POSITION, version 1.1).
496  * @ingroup solution_messages
497  *
498  * @note
499  * All data is timestamped using the Point One Time, which is a monotonic
500  * timestamp referenced to the start of the device. Corresponding messages (@ref
501  * PoseMessage, @ref GNSSSatelliteMessage, etc.) may be associated using
502  * their @ref p1_time values.
503  */
505  static constexpr MessageType MESSAGE_TYPE =
507  static constexpr uint8_t MESSAGE_VERSION = 1;
508 
509  static constexpr uint32_t INVALID_REFERENCE_STATION = 0xFFFFFFFF;
510 
511  /** The time of the message, in P1 time (beginning at power-on). */
513 
514  /** The GPS time of the message, if available, referenced to 1980/1/6. */
516 
517  /** The type of this position solution. */
519 
520  uint8_t reserved[3] = {0};
521 
522  /** The ID of the differential base station. */
523  uint32_t reference_station_id = INVALID_REFERENCE_STATION;
524 
525  /**
526  * The relative position (in meters), resolved in the local ENU frame.
527  *
528  * @note
529  * If a differential solution to the base station is not available, these
530  * values will be `NAN`.
531  */
532  double relative_position_enu_m[3] = {NAN, NAN, NAN};
533 
534  /**
535  * The position standard deviation (in meters), resolved with respect to the
536  * local ENU tangent plane: east, north, up.
537  *
538  * @note
539  * If a differential solution to the base station is not available, these
540  * values will be `NAN`.
541  */
542  float position_std_enu_m[3] = {NAN, NAN, NAN};
543 };
544 
545 #pragma pack(pop)
546 
547 } // namespace messages
548 } // namespace fusion_engine
549 } // namespace point_one
@ POSE_AUX
PoseAuxMessage
MessageType
Identifiers for the defined output message types.
Definition: defs.h:34
Library portability helper definitions.
SolutionType
Navigation solution type definitions.
Definition: defs.h:464
@ UNKNOWN
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:294
@ MOUNTING_ANGLE
Estimating IMU mounting angles.
#define P1_ALIGNAS(N)
Definition: portability.h:57
Device calibration status update.
Definition: solution.h:405
@ DONE
Calibration complete.
@ GNSS_INFO
GNSSInfoMessage
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:46
@ CALIBRATION_STATUS
CalibrationStatusMessage
@ GNSS_SATELLITE
GNSSSatelliteMessage
The base class for all message payloads.
Definition: defs.h:648
Information about an individual satellite (see GNSSSatelliteMessage).
Definition: solution.h:313
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:512
@ POSE
PoseMessage
@ Invalid
Invalid, no position available.
GNSS signal and frequency type definitions.
Definition: logging.h:38
Auxiliary platform pose information (MessageType::POSE_AUX, version 1.0).
Definition: solution.h:162
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:167
P1_CONSTEXPR_FUNC const char * to_string(ConfigType type)
Get a human-friendly string name for the specified ConfigType.
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
Definition: solution.h:224
std::ostream p1_ostream
Definition: portability.h:75
p1_ostream & operator<<(p1_ostream &stream, ConfigType type)
ConfigType stream operator.
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
Definition: solution.h:297
CalibrationStage
The stages of the device calibration process.
Definition: solution.h:364
#define P1_CONSTEXPR_FUNC
Definition: portability.h:105
Platform pose solution: position, velocity, attitude (MessageType::POSE, version 1....
Definition: solution.h:40
SatelliteType
System/constellation type definitions.
Definition: signal_defs.h:27
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
Definition: solution.h:49
Timestamp p1_time
The most recent P1 time, if available.
Definition: solution.h:410
@ RELATIVE_ENU_POSITION
RelativeENUPositionMessage
Information about the GNSS data used in the PoseMessage with the corresponding timestamp (MessageType...
Definition: solution.h:211
@ UNKNOWN
Calibration stage not known.
Relative ENU position to base station (MessageType::RELATIVE_ENU_POSITION, version 1....
Definition: solution.h:504
Point One FusionEngine output message common definitions.
Information about the individual satellites used in the PoseMessage and GNSSInfoMessage with the corr...
Definition: solution.h:289
Generic timestamp representation.
Definition: defs.h:549
SolutionType solution_type
The type of this position solution.
Definition: solution.h:52
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
Definition: solution.h:515
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:221