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