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 so
15 // that floating point values are aligned on platforms that require it.
16 #pragma pack(push, 4)
17 
18 /**
19  * @brief Platform pose solution: position, velocity, attitude (@ref
20  * MessageType::POSE), version 1.1.
21  * @ingroup messages
22  *
23  * @note
24  * All data is timestamped using the Point One Time, which is a monotonic
25  * timestamp referenced to the start of the device. Corresponding messages (@ref
26  * GNSSInfoMessage, @ref GNSSSatelliteMessage, etc.) may be associated using
27  * their @ref p1_time values.
28  */
29 struct PoseMessage {
30  static constexpr int16_t INVALID_UNDULATION = INT16_MIN;
31 
32  /** The time of the message, in P1 time (beginning at power-on). */
34 
35  /** The GPS time of the message, if available, referenced to 1980/1/6. */
37 
38  /** The type of this position solution. */
40 
41  uint8_t reserved = 0;
42 
43  /**
44  * The geoid undulation at at the current location (i.e., the difference
45  * between the WGS-84 ellipsoid and the geoid).
46  *
47  * Height above the ellipsoid can be converted to a corresponding height above
48  * the geoid (orthometric height or height above mean sea level (MSL)) as
49  * follows:
50  *
51  * @f[
52  * h_{orthometric} = h_{ellipsoid} - undulation
53  * @f]
54  *
55  * Stored in units of 0.01 meters: `undulation_m = undulation_cm * 0.01`. Set
56  * to `-32768` if invalid.
57  *
58  * Added in @ref PoseMessage version 1.1.
59  */
61 
62  /**
63  * The geodetic latitude, longitude, and altitude (in degrees/meters),
64  * expressed using the WGS-84 reference ellipsoid.
65  *
66  * @section p1_fe_pose_datum Datum/Epoch Considerations
67  * When comparing two positions, it is very important to make sure they are
68  * compared using the same geodetic datum, defined at the same time (epoch).
69  * Failing to do so can cause very large unexpected differences since the
70  * ground moves in various directions over time due to motion of tectonic
71  * plates.
72  *
73  * For example, the coordinates for a point on the ground in San Francisco
74  * expressed in the ITRF14 datum may differ by multiple meters from the
75  * coordinates for the same point expressed the NAD83 datum. Similarly, the
76  * coordinates for that location expressed in the ITRF14 2017.0 epoch
77  * (January 1, 2017) may differ by 12 cm or more when expressed using the
78  * ITRF14 2021.0 epoch (January 1, 2021).
79  *
80  * The datum and epoch to which the position reported in this message is
81  * aligned depends on the current @ref solution_type.
82  * - @ref SolutionType::AutonomousGPS / @ref SolutionType::DGPS /
83  * @ref SolutionType::PPP - Standalone solutions (i.e., no differential
84  * corrections) are aligned to the WGS-84 datum as broadcast live by GPS
85  * (aligns closely with the ITRF08/14 datums).
86  * - @ref SolutionType::RTKFloat / @ref SolutionType::RTKFixed - When
87  * differential corrections are applied, the reference datum and epoch are
88  * defined by the corrections provider. Point One's Polaris Corrections
89  * Service produces corrections using the ITRF14 datum. See
90  * https://pointonenav.com/polaris for more details.
91  * - @ref SolutionType::Integrate - When the INS is dead reckoning in the
92  * absence of GNSS, vision, or other measurements anchored in absolute world
93  * coordinates, the position solution is defined in the same datum/epoch
94  * specified by the previous solution type (e.g., WGS-84 if previously
95  * standalone GNSS, i.e., @ref SolutionType::AutonomousGPS).
96  */
97  double lla_deg[3] = {NAN, NAN, NAN};
98 
99  /**
100  * The position standard deviation (in meters), resolved with respect to the
101  * local ENU tangent plane: east, north, up.
102  */
103  float position_std_enu_m[3] = {NAN, NAN, NAN};
104 
105  /**
106  * The platform attitude (in degrees), if known, described as intrinsic
107  * Euler-321 angles (yaw, pitch, roll) with respect to the local ENU tangent
108  * plane. Set to `NAN` if attitude is not available.
109  *
110  * @note
111  * The platform body axes are defined as +x forward, +y left, and +z up. A
112  * positive yaw is a left turn, positive pitch points the nose of the vehicle
113  * down, and positive roll is a roll toward the right. Yaw is measured from
114  * east in a counter-clockwise direction. For example, north is +90 degrees
115  * (i.e., `heading = 90.0 - ypr_deg[0]`).
116  */
117  double ypr_deg[3] = {NAN, NAN, NAN};
118 
119  /**
120  * The attitude standard deviation (in degrees): yaw, pitch, roll.
121  */
122  float ypr_std_deg[3] = {NAN, NAN, NAN};
123 
124  /**
125  * The platform velocity (in meters/second), resolved in the body frame. Set
126  * to `NAN` if attitude is not available for the body frame transformation.
127  */
128  double velocity_body_mps[3] = {NAN, NAN, NAN};
129 
130  /**
131  * The velocity standard deviation (in meters/second), resolved in the body
132  * frame.
133  */
134  float velocity_std_body_mps[3] = {NAN, NAN, NAN};
135 
136  /** The estimated aggregate 3D protection level (in meters). */
138  /** The estimated 2D horizontal protection level (in meters). */
140  /** The estimated vertical protection level (in meters). */
142 };
143 
144 /**
145  * @brief Auxiliary platform pose information (@ref MessageType::POSE_AUX),
146  * version 1.0.
147  * @ingroup messages
148  */
150  /** The time of the message, in P1 time (beginning at power-on). */
152 
153  /**
154  * The position standard deviation (in meters), resolved in the body frame.
155  * Set to `NAN` if attitude is not available for the body frame
156  * transformation.
157  */
158  float position_std_body_m[3] = {NAN, NAN, NAN};
159 
160  /**
161  * The 3x3 position covariance matrix (in m^2), resolved in the local ENU
162  * frame. Values are stored in row-major order.
163  */
164  double position_cov_enu_m2[9] = {NAN};
165 
166  /**
167  * The platform body orientation with respect to the local ENU frame,
168  * represented as a quaternion with the scalar component last (x, y, z, w).
169  */
170  double attitude_quaternion[4] = {NAN, NAN, NAN, NAN};
171 
172  /**
173  * The platform velocity (in meters/second), resolved in the local ENU frame.
174  */
175  double velocity_enu_mps[3] = {NAN, NAN, NAN};
176 
177  /**
178  * The velocity standard deviation (in meters/second), resolved in the local
179  * ENU frame.
180  */
181  float velocity_std_enu_mps[3] = {NAN, NAN, NAN};
182 };
183 
184 /**
185  * @brief Information about the GNSS data used in the @ref PoseMessage with the
186  * corresponding timestamp (@ref MessageType::GNSS_INFO).
187  * @ingroup messages
188  */
190  static constexpr uint32_t INVALID_REFERENCE_STATION = 0xFFFFFFFF;
191 
192  /** The time of the message, in P1 time (beginning at power-on). */
194 
195  /** The GPS time of the message, if available, referenced to 1980/1/6. */
197 
198  /** The P1 time of the last differential GNSS update. */
200 
201  /** The ID of the differential base station, if used. */
203 
204  /** The geometric dilution of precision (GDOP). */
205  float gdop = NAN;
206  /** The position dilution of precision (PDOP). */
207  float pdop = NAN;
208  /** The horizontal dilution of precision (HDOP). */
209  float hdop = NAN;
210  /** The vertical dilution of precision (VDOP). */
211  float vdop = NAN;
212 
213  /** GPS time alignment standard deviation (in seconds). */
214  float gps_time_std_sec = NAN;
215 };
216 
217 /**
218  * @brief Information about the individual satellites used in the @ref
219  * PoseMessage and @ref GNSSInfoMessage with the corresponding timestamp
220  * (@ref MessageType::GNSS_SATELLITE), version 1.1.
221  * @ingroup messages
222  *
223  * This message is followed by `N` @ref SatelliteInfo objects, where `N` is
224  * equal to @ref num_satellites. For example, a message with two satellites
225  * would be serialized as:
226  *
227  * ```
228  * {MessageHeader, GNSSSatelliteMessage, SatelliteInfo, SatelliteInfo, ...}
229  * ```
230  */
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  /** The number of known satellites. */
239  uint16_t num_satellites = 0;
240 
241  uint8_t reserved[2] = {0};
242 };
243 
244 /**
245  * @brief Information about an individual satellite (see @ref
246  * GNSSSatelliteMessage).
247  *
248  * For satellites where @ref usage is 0, the satellite may either be currently
249  * tracked by the receiver but not used for navigation, or may just be expected
250  * according to available ephemeris data.
251  */
253  /**
254  * @defgroup satellite_usage Bit definitions for the satellite usage bitmask
255  * (@ref SatelliteInfo::usage).
256  * @{
257  */
258  static constexpr uint8_t SATELLITE_USED = 0x01;
259  /** @} */
260 
261  static constexpr int16_t INVALID_CN0 = 0;
262 
263  /** The GNSS system to which this satellite belongs. */
265 
266  /** The satellite's PRN (or slot number for GLONASS). */
267  uint8_t prn = 0;
268 
269  /**
270  * A bitmask specifying how this satellite was used in the position solution.
271  * Set to 0 if the satellite was not used. See @ref satellite_usage.
272  */
273  uint8_t usage = 0;
274 
275  /**
276  * The carrier-to-noise density ratio (C/N0) for the L1 signal on the
277  * satellite.
278  *
279  * Stored in units of 0.25 dB-Hz: `cn0_dbhz = cn0 * 0.25`. Set to 0 if
280  * invalid. The range of this field is 0.25-63.75 dB-Hz. Values outside of
281  * this range will be clipped to the min/max values.
282  *
283  * @note
284  * If the satellite is not tracking L1 (or the L1-equivalent for other
285  * constellations, e.g., G1 for GLONASS) but another frequency is being used,
286  * that signal's C/N0 value will be reported.
287  *
288  * Added in @ref GNSSSatelliteMessage version 1.1.
289  */
290  uint8_t cn0 = INVALID_CN0;
291 
292  /** The azimuth of the satellite (in degrees). */
293  float azimuth_deg = NAN;
294 
295  /** The elevation of the satellite (in degrees). */
296  float elevation_deg = NAN;
297 };
298 
299 #pragma pack(pop)
300 
301 } // namespace messages
302 } // namespace fusion_engine
303 } // namespace point_one
float velocity_std_body_mps[3]
The velocity standard deviation (in meters/second), resolved in the body frame.
Definition: solution.h:134
float vdop
The vertical dilution of precision (VDOP).
Definition: solution.h:211
double lla_deg[3]
The geodetic latitude, longitude, and altitude (in degrees/meters), expressed using the WGS-84 refere...
Definition: solution.h:97
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:103
SolutionType
Navigation solution type definitions.
Definition: defs.h:46
static constexpr uint32_t INVALID_REFERENCE_STATION
Definition: solution.h:190
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:233
static constexpr uint8_t SATELLITE_USED
Definition: solution.h:258
float gdop
The geometric dilution of precision (GDOP).
Definition: solution.h:205
@ UNKNOWN
uint8_t usage
A bitmask specifying how this satellite was used in the position solution.
Definition: solution.h:273
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:33
SatelliteType system
The GNSS system to which this satellite belongs.
Definition: solution.h:264
SatelliteType
System/constellation type definitions.
Definition: defs.h:29
double attitude_quaternion[4]
The platform body orientation with respect to the local ENU frame, represented as a quaternion with t...
Definition: solution.h:170
uint8_t cn0
The carrier-to-noise density ratio (C/N0) for the L1 signal on the satellite.
Definition: solution.h:290
Information about an individual satellite (see GNSSSatelliteMessage).
Definition: solution.h:252
Definition: crc.cc:52
static constexpr int16_t INVALID_UNDULATION
Definition: solution.h:30
Auxiliary platform pose information (MessageType::POSE_AUX), version 1.0.
Definition: solution.h:149
float gps_time_std_sec
GPS time alignment standard deviation (in seconds).
Definition: solution.h:214
float hdop
The horizontal dilution of precision (HDOP).
Definition: solution.h:209
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:151
uint16_t num_satellites
The number of known satellites.
Definition: solution.h:239
float position_std_body_m[3]
The position standard deviation (in meters), resolved in the body frame.
Definition: solution.h:158
float pdop
The position dilution of precision (PDOP).
Definition: solution.h:207
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
Definition: solution.h:196
double velocity_enu_mps[3]
The platform velocity (in meters/second), resolved in the local ENU frame.
Definition: solution.h:175
static constexpr int16_t INVALID_CN0
Definition: solution.h:261
double ypr_deg[3]
The platform attitude (in degrees), if known, described as intrinsic Euler-321 angles (yaw,...
Definition: solution.h:117
Timestamp last_differential_time
The P1 time of the last differential GNSS update.
Definition: solution.h:199
uint8_t prn
The satellite's PRN (or slot number for GLONASS).
Definition: solution.h:267
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
Definition: solution.h:236
float ypr_std_deg[3]
The attitude standard deviation (in degrees): yaw, pitch, roll.
Definition: solution.h:122
float elevation_deg
The elevation of the satellite (in degrees).
Definition: solution.h:296
float aggregate_protection_level_m
The estimated aggregate 3D protection level (in meters).
Definition: solution.h:137
float azimuth_deg
The azimuth of the satellite (in degrees).
Definition: solution.h:293
Platform pose solution: position, velocity, attitude (MessageType::POSE), version 1....
Definition: solution.h:29
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
Definition: solution.h:36
float vertical_protection_level_m
The estimated vertical protection level (in meters).
Definition: solution.h:141
double position_cov_enu_m2[9]
The 3x3 position covariance matrix (in m^2), resolved in the local ENU frame.
Definition: solution.h:164
Information about the GNSS data used in the PoseMessage with the corresponding timestamp (MessageType...
Definition: solution.h:189
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:60
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:181
Information about the individual satellites used in the PoseMessage and GNSSInfoMessage with the corr...
Definition: solution.h:231
Generic timestamp representation.
Definition: defs.h:107
double velocity_body_mps[3]
The platform velocity (in meters/second), resolved in the body frame.
Definition: solution.h:128
float horizontal_protection_level_m
The estimated 2D horizontal protection level (in meters).
Definition: solution.h:139
SolutionType solution_type
The type of this position solution.
Definition: solution.h:39
uint32_t reference_station_id
The ID of the differential base station, if used.
Definition: solution.h:202
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:193