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).
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  /** The time of the message, in P1 time (beginning at power-on). */
32 
33  /** The GPS time of the message, if available, referenced to 1980/1/6. */
35 
36  /** The type of this position solution. */
38 
39  uint8_t reserved[3] = {0};
40 
41  /**
42  * The WGS-84 geodetic latitude, longitude, and altitude (in degrees/meters).
43  */
44  double lla_deg[3] = {NAN, NAN, NAN};
45 
46  /**
47  * The position standard deviation (in meters), resolved with respect to the
48  * local ENU tangent plane: east, north, up.
49  */
50  float position_std_enu_m[3] = {NAN, NAN, NAN};
51 
52  /**
53  * The platform attitude (in degrees), if known, described as intrinsic
54  * Euler-321 angles (yaw, pitch, roll) with respect to the local ENU tangent
55  * plane. Set to `NAN` if attitude is not available.
56  *
57  * @note
58  * The platform body axes are defined as +x forward, +y left, and +z up. A
59  * positive yaw is a left turn, positive pitch points the nose of the vehicle
60  * down, and positive roll is a roll toward the right. Yaw is measured from
61  * east in a counter-clockwise direction. For example, north is +90 degrees
62  * (i.e., `heading = 90.0 - ypr_deg[0]`).
63  */
64  double ypr_deg[3] = {NAN, NAN, NAN};
65 
66  /**
67  * The attitude standard deviation (in degrees): yaw, pitch, roll.
68  */
69  float ypr_std_deg[3] = {NAN, NAN, NAN};
70 
71  /**
72  * The platform velocity (in meters/second), resolved in the body frame. Set
73  * to `NAN` if attitude is not available for the body frame transformation.
74  */
75  double velocity_body_mps[3] = {NAN, NAN, NAN};
76 
77  /**
78  * The velocity standard deviation (in meters/second), resolved in the body
79  * frame.
80  */
81  float velocity_std_body_mps[3] = {NAN, NAN, NAN};
82 
83  /** The estimated aggregate 3D protection level (in meters). */
85  /** The estimated 2D horizontal protection level (in meters). */
87  /** The estimated vertical protection level (in meters). */
89 };
90 
91 /**
92  * @brief Auxiliary platform pose information (@ref MessageType::POSE_AUX).
93  * @ingroup messages
94  */
96  /** The time of the message, in P1 time (beginning at power-on). */
98 
99  /**
100  * The position standard deviation (in meters), resolved in the body frame.
101  * Set to `NAN` if attitude is not available for the body frame
102  * transformation.
103  */
104  float position_std_body_m[3] = {NAN, NAN, NAN};
105 
106  /**
107  * The 3x3 position covariance matrix (in m^2), resolved in the local ENU
108  * frame. Values are stored in row-major order.
109  */
110  double position_cov_enu_m2[9] = {NAN};
111 
112  /**
113  * The platform body orientation with respect to the local ENU frame,
114  * represented as a quaternion with the scalar component last (x, y, z, w).
115  */
116  double attitude_quaternion[4] = {NAN, NAN, NAN, NAN};
117 
118  /**
119  * The platform velocity (in meters/second), resolved in the local ENU frame.
120  */
121  double velocity_enu_mps[3] = {NAN, NAN, NAN};
122 
123  /**
124  * The velocity standard deviation (in meters/second), resolved in the local
125  * ENU frame.
126  */
127  float velocity_std_enu_mps[3] = {NAN, NAN, NAN};
128 };
129 
130 /**
131  * @brief Information about the GNSS data used in the @ref PoseMessage with the
132  * corresponding timestamp (@ref MessageType::GNSS_INFO).
133  * @ingroup messages
134  */
136  static constexpr uint32_t INVALID_REFERENCE_STATION = 0xFFFFFFFF;
137 
138  /** The time of the message, in P1 time (beginning at power-on). */
140 
141  /** The GPS time of the message, if available, referenced to 1980/1/6. */
143 
144  /** The P1 time of the last differential GNSS update. */
146 
147  /** The ID of the differential base station, if used. */
149 
150  /** The geometric dilution of precision (GDOP). */
151  float gdop = NAN;
152  /** The position dilution of precision (PDOP). */
153  float pdop = NAN;
154  /** The horizontal dilution of precision (HDOP). */
155  float hdop = NAN;
156  /** The vertical dilution of precision (VDOP). */
157  float vdop = NAN;
158 
159  /** GPS time alignment standard deviation (in seconds). */
160  float gps_time_std_sec = NAN;
161 };
162 
163 /**
164  * @brief Information about the individual satellites used in the @ref
165  * PoseMessage and @ref GNSSInfoMessage with the corresponding timestamp
166  * (@ref MessageType::GNSS_SATELLITE).
167  * @ingroup messages
168  *
169  * This message is followed by `N` @ref SatelliteInfo objects, where `N` is
170  * equal to @ref num_satellites. For example, a message with two satellites
171  * would be serialized as:
172  *
173  * ```
174  * {MessageHeader, GNSSSatelliteMessage, SatelliteInfo, SatelliteInfo, ...}
175  * ```
176  */
178  /** The time of the message, in P1 time (beginning at power-on). */
180 
181  /** The GPS time of the message, if available, referenced to 1980/1/6. */
183 
184  /** The number of known satellites. */
185  uint16_t num_satellites = 0;
186 
187  uint8_t reserved[2] = {0};
188 };
189 
190 /**
191  * @brief Information about an individual satellite (see @ref
192  * GNSSSatelliteMessage).
193  *
194  * For satellites where @ref usage is 0, the satellite may either be currently
195  * tracked by the receiver but not used for navigation, or may just be expected
196  * according to available ephemeris data.
197  */
199  /**
200  * @defgroup satellite_usage Bit definitions for the satellite usage bitmask
201  * (@ref SatelliteInfo::usage).
202  * @{
203  */
204  static constexpr uint8_t SATELLITE_USED = 0x01;
205  /** @} */
206 
207  /** The GNSS system to which this satellite belongs. */
209 
210  /** The satellite's PRN (or slot number for GLONASS). */
211  uint8_t prn = 0;
212 
213  /**
214  * A bitmask specifying how this satellite was used in the position solution.
215  * Set to 0 if the satellite was not used. See @ref satellite_usage.
216  */
217  uint8_t usage = 0;
218 
219  uint8_t reserved = 0;
220 
221  /** The azimuth of the satellite (in degrees). */
222  float azimuth_deg = NAN;
223 
224  /** The elevation of the satellite (in degrees). */
225  float elevation_deg = NAN;
226 };
227 
228 #pragma pack(pop)
229 
230 } // namespace messages
231 } // namespace fusion_engine
232 } // namespace point_one
float velocity_std_body_mps[3]
The velocity standard deviation (in meters/second), resolved in the body frame.
Definition: solution.h:81
float vdop
The vertical dilution of precision (VDOP).
Definition: solution.h:157
double lla_deg[3]
The WGS-84 geodetic latitude, longitude, and altitude (in degrees/meters).
Definition: solution.h:44
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:50
SolutionType
Navigation solution type definitions.
Definition: defs.h:45
static constexpr uint32_t INVALID_REFERENCE_STATION
Definition: solution.h:136
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:179
static constexpr uint8_t SATELLITE_USED
Definition: solution.h:204
float gdop
The geometric dilution of precision (GDOP).
Definition: solution.h:151
@ UNKNOWN
uint8_t usage
A bitmask specifying how this satellite was used in the position solution.
Definition: solution.h:217
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:31
SatelliteType system
The GNSS system to which this satellite belongs.
Definition: solution.h:208
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:116
Information about an individual satellite (see GNSSSatelliteMessage).
Definition: solution.h:198
Definition: crc.cc:49
Auxiliary platform pose information (MessageType::POSE_AUX).
Definition: solution.h:95
float gps_time_std_sec
GPS time alignment standard deviation (in seconds).
Definition: solution.h:160
float hdop
The horizontal dilution of precision (HDOP).
Definition: solution.h:155
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:97
uint16_t num_satellites
The number of known satellites.
Definition: solution.h:185
float position_std_body_m[3]
The position standard deviation (in meters), resolved in the body frame.
Definition: solution.h:104
float pdop
The position dilution of precision (PDOP).
Definition: solution.h:153
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
Definition: solution.h:142
double velocity_enu_mps[3]
The platform velocity (in meters/second), resolved in the local ENU frame.
Definition: solution.h:121
double ypr_deg[3]
The platform attitude (in degrees), if known, described as intrinsic Euler-321 angles (yaw,...
Definition: solution.h:64
Timestamp last_differential_time
The P1 time of the last differential GNSS update.
Definition: solution.h:145
uint8_t prn
The satellite's PRN (or slot number for GLONASS).
Definition: solution.h:211
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
Definition: solution.h:182
float ypr_std_deg[3]
The attitude standard deviation (in degrees): yaw, pitch, roll.
Definition: solution.h:69
float elevation_deg
The elevation of the satellite (in degrees).
Definition: solution.h:225
float aggregate_protection_level_m
The estimated aggregate 3D protection level (in meters).
Definition: solution.h:84
float azimuth_deg
The azimuth of the satellite (in degrees).
Definition: solution.h:222
Platform pose solution: position, velocity, attitude (MessageType::POSE).
Definition: solution.h:29
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
Definition: solution.h:34
float vertical_protection_level_m
The estimated vertical protection level (in meters).
Definition: solution.h:88
double position_cov_enu_m2[9]
The 3x3 position covariance matrix (in m^2), resolved in the local ENU frame.
Definition: solution.h:110
Information about the GNSS data used in the PoseMessage with the corresponding timestamp (MessageType...
Definition: solution.h:135
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:127
Information about the individual satellites used in the PoseMessage and GNSSInfoMessage with the corr...
Definition: solution.h:177
Generic timestamp representation.
Definition: defs.h:95
double velocity_body_mps[3]
The platform velocity (in meters/second), resolved in the body frame.
Definition: solution.h:75
float horizontal_protection_level_m
The estimated 2D horizontal protection level (in meters).
Definition: solution.h:86
SolutionType solution_type
The type of this position solution.
Definition: solution.h:37
uint32_t reference_station_id
The ID of the differential base station, if used.
Definition: solution.h:148
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: solution.h:139