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