measurements.h
Go to the documentation of this file.
1 /**************************************************************************/ /**
2  * @brief Sensor measurement 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 measurement_messages Sensor Measurement Message Definitions
23  * @brief Measurement data from available sensors.
24  * @ingroup messages
25  *
26  * See also @ref messages.
27  */
28 
29 /**
30  * @brief The source of a @ref point_one::fusion_engine::messages::Timestamp
31  * used to represent the time of applicability of an incoming sensor
32  * measurement.
33  * @ingroup measurement_messages
34  */
35 enum class SystemTimeSource : uint8_t {
36  /** Timestamp not valid. */
37  INVALID = 0,
38  /** Message timestamped in P1 time. */
39  P1_TIME = 1,
40  /**
41  * Message timestamped in system time, generated when received by the device.
42  */
44  /**
45  * Message timestamp was generated from a monotonic clock of an external
46  * system.
47  */
49  /**
50  * Message timestamped in GPS time, referenced to 1980/1/6.
51  */
52  GPS_TIME = 4,
53 };
54 
55 /**
56  * @brief Get a human-friendly string name for the specified @ref
57  * SystemTimeSource.
58  *
59  * @param val The enum to get the string name for.
60  *
61  * @return The corresponding string name.
62  */
64  switch (val) {
66  return "Invalid";
68  return "P1 Time";
70  return "Timestamped on Reception";
72  return "Sender System Time";
74  return "GPS Time";
75  default:
76  return "Unrecognized";
77  }
78 }
79 
80 /**
81  * @brief @ref SystemTimeSource stream operator.
82  */
83 inline std::ostream& operator<<(std::ostream& stream, SystemTimeSource val) {
84  stream << to_string(val) << " (" << (int)val << ")";
85  return stream;
86 }
87 
88 /**
89  * @brief The time of applicability for an incoming sensor measurement.
90  *
91  * By convention this will be the first member of any measurement definition
92  * intended to be externally sent by the user to the device.
93  *
94  * The @ref measurement_time field stores time of applicability/reception for
95  * the measurement data, expressed in one of the available source time bases
96  * (see @ref SystemTimeSource). The timestamp will be converted to P1 time
97  * automatically by FusionEngine using an internal model of P1 vs source time.
98  * The converted value will be assigned to @ref p1_time for usage and logging
99  * purposes.
100  *
101  * On most platforms, incoming sensor measurements are timestamped automatically
102  * by FusionEngine when they arrive. To request timestamp on arrival, set @ref
103  * measurement_time to invalid, and set the @ref measurement_time_source to
104  * @ref SystemTimeSource::INVALID.
105  *
106  * On some platforms, incoming sensor measurements may be timestamped
107  * externally by the user prior to arrival, either in GPS time (@ref
108  * SystemTimeSource::GPS_TIME), or using a monotonic clock controlled by the
109  * user system (@ref SystemTimeSource::SENDER_SYSTEM_TIME).
110  *
111  * @note
112  * Use of an external monotonic clock requires additional coordination with the
113  * target FusionEngine device.
114  *
115  * Measurements may only be timestamped externally using P1 time (@ref
116  * SystemTimeSource::P1_TIME) if the external system supports remote
117  * synchronization of the P1 time clock model.
118  */
119 struct alignas(4) MeasurementTimestamps {
120  /**
121  * The measurement time of applicability, if available, in a user-specified
122  * time base. The source of this value is specified in @ref
123  * measurement_time_source. The timestamp will be converted to P1 time
124  * automatically before use.
125  */
127 
128  /**
129  * The source for @ref measurement_time.
130  */
132 
133  uint8_t reserved[3] = {0};
134 
135  /**
136  * The P1 time corresponding with the measurement time of applicability, if
137  * available.
138  *
139  * @note
140  * Do not modify this field when sending measurements to FusionEngine. It will
141  * be populated automatically on arrival. Any previously specified value will
142  * be overwritten. To specify a known P1 time, specify the value in @ref
143  * measurement_time and set @ref measurement_time_source to @ref
144  * SystemTimeSource::P1_TIME.
145  */
147 };
148 
149 /**
150  * @brief IMU sensor measurement data (@ref MessageType::IMU_MEASUREMENT,
151  * version 1.0).
152  * @ingroup measurement_messages
153  *
154  * @note
155  * The data contained in this message has been corrected for accelerometer and
156  * gyro biases and scale factors, and has been rotated into the vehicle body
157  * frame from the original IMU orientation.
158  */
159 struct alignas(4) IMUMeasurement : public MessagePayload {
161  static constexpr uint8_t MESSAGE_VERSION = 0;
162 
163  /** The time of the message, in P1 time (beginning at power-on). */
165 
166  /**
167  * Corrected vehicle x/y/z acceleration (in meters/second^2), resolved in the
168  * body frame.
169  */
170  double accel_mps2[3] = {NAN, NAN, NAN};
171 
172  /**
173  * Corrected vehicle x/y/z acceleration standard deviation (in
174  * meters/second^2), resolved in the body frame.
175  */
176  double accel_std_mps2[3] = {NAN, NAN, NAN};
177 
178  /**
179  * Corrected vehicle x/y/z rate of rotation (in radians/second), resolved in
180  * the body frame.
181  */
182  double gyro_rps[3] = {NAN, NAN, NAN};
183 
184  /**
185  * Corrected vehicle x/y/z rate of rotation standard deviation (in
186  * radians/second), resolved in the body frame.
187  */
188  double gyro_std_rps[3] = {NAN, NAN, NAN};
189 };
190 
191 /**
192  * @brief The current transmission gear used by the vehicle.
193  * @ingroup measurement_messages
194  */
195 enum class GearType : uint8_t {
196  /**
197  * The transmission gear is not known, or does not map to a supported
198  * GearType.
199  */
200  UNKNOWN = 0,
201  FORWARD = 1, ///< The vehicle is in a forward gear.
202  REVERSE = 2, ///< The vehicle is in reverse.
203  PARK = 3, ///< The vehicle is parked.
204  NEUTRAL = 4, ///< The vehicle is in neutral.
205 };
206 
207 /**
208  * @brief Get a human-friendly string name for the specified @ref GearType.
209  *
210  * @param val The enum to get the string name for.
211  *
212  * @return The corresponding string name.
213  */
215  switch (val) {
216  case GearType::UNKNOWN:
217  return "Unknown";
218  case GearType::FORWARD:
219  return "Forward";
220  case GearType::REVERSE:
221  return "Reverse";
222  case GearType::PARK:
223  return "Park";
224  case GearType::NEUTRAL:
225  return "Neutral";
226  default:
227  return "Unrecognized";
228  }
229 }
230 
231 /**
232  * @brief @ref GearType stream operator.
233  */
234 inline std::ostream& operator<<(std::ostream& stream, GearType val) {
235  stream << to_string(val) << " (" << (int)val << ")";
236  return stream;
237 }
238 
239 /**
240  * @brief Differential wheel speed measurement (@ref
241  * MessageType::WHEEL_SPEED_MEASUREMENT, version 1.0).
242  * @ingroup measurement_messages
243  *
244  * This message may be used to convey the speed of each individual wheel on the
245  * vehicle. The number and type of wheels expected varies by vehicle. To use
246  * wheel speed data, you must first configure the device by issuing a @ref
247  * SetConfigMessage message containing a @ref WheelConfig payload describing the
248  * vehicle sensor configuration.
249  *
250  * Some platforms may support an additional, optional voltage signal used to
251  * indicate direction of motion. Alternatively, when receiving CAN data from a
252  * vehicle, direction may be conveyed explicitly in a CAN message, or may be
253  * indicated based on the current transmission gear setting.
254  */
255 struct alignas(4) WheelSpeedMeasurement : public MessagePayload {
256  static constexpr MessageType MESSAGE_TYPE =
258  static constexpr uint8_t MESSAGE_VERSION = 0;
259 
260  /** Measurement timestamps, if available. See @ref measurement_messages. */
262 
263  /** The front left wheel speed (in m/s). Set to NAN if not available. */
264  float front_left_speed_mps = NAN;
265 
266  /** The front right wheel speed (in m/s). Set to NAN if not available. */
268 
269  /** The rear left wheel speed (in m/s). Set to NAN if not available. */
270  float rear_left_speed_mps = NAN;
271 
272  /** The rear right wheel speed (in m/s). Set to NAN if not available. */
273  float rear_right_speed_mps = NAN;
274 
275  /**
276  * The transmission gear currently in use, or direction of motion, if
277  * available.
278  *
279  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
280  * direction information is available externally.
281  */
283 
284  /**
285  * `true` if the wheel speeds are signed (positive forward, negative reverse),
286  * or `false` if the values are unsigned (positive in both directions).
287  */
288  bool is_signed = true;
289 
290  uint8_t reserved[2] = {0};
291 };
292 
293 /**
294  * @brief Vehicle body speed measurement (@ref
295  * MessageType::VEHICLE_SPEED_MEASUREMENT, version 1.0).
296  * @ingroup measurement_messages
297  *
298  * This message may be used to convey the along-track speed of the vehicle
299  * (forward/backward). To use vehicle speed data, you must first configure the
300  * device by issuing a @ref SetConfigMessage message containing a @ref
301  * WheelConfig payload describing the vehicle sensor configuration.
302  *
303  * Some platforms may support an additional, optional voltage signal used to
304  * indicate direction of motion. Alternatively, when receiving CAN data from a
305  * vehicle, direction may be conveyed explicitly in a CAN message, or may be
306  * indicated based on the current transmission gear setting.
307  */
308 struct alignas(4) VehicleSpeedMeasurement : public MessagePayload {
309  static constexpr MessageType MESSAGE_TYPE =
311  static constexpr uint8_t MESSAGE_VERSION = 0;
312 
313  /** Measurement timestamps, if available. See @ref measurement_messages. */
315 
316  /** The current vehicle speed estimate (in m/s). */
317  float vehicle_speed_mps = NAN;
318 
319  /**
320  * The transmission gear currently in use, or direction of motion, if
321  * available.
322  *
323  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
324  * direction information is available externally.
325  */
327 
328  /**
329  * `true` if the wheel speeds are signed (positive forward, negative reverse),
330  * or `false` if the values are unsigned (positive in both directions).
331  */
332  bool is_signed = true;
333 
334  uint8_t reserved[2] = {0};
335 };
336 
337 /**
338  * @brief Differential wheel encoder tick measurement (@ref
339  * MessageType::WHEEL_TICK_MEASUREMENT, version 1.0).
340  * @ingroup measurement_messages
341  *
342  * This message may be used to convey a one or more wheel encoder tick counts
343  * received either by software (e.g., vehicle CAN bus), or captured in hardware
344  * from external voltage pulses. The number and type of wheels expected, and the
345  * interpretation of the tick count values, varies by vehicle. To use wheel
346  * encoder data, you ust first configure the device by issuing a @ref
347  * SetConfigMessage message containing a @ref WheelConfig payload describing the
348  * vehicle sensor configuration.
349  *
350  * Some platforms may support an additional, optional voltage signal used to
351  * indicate direction of motion. Alternatively, when receiving CAN data from a
352  * vehicle, direction may be conveyed explicitly in a CAN message, or may be
353  * indicated based on the current transmission gear setting.
354  */
355 struct alignas(4) WheelTickMeasurement : public MessagePayload {
356  static constexpr MessageType MESSAGE_TYPE =
358  static constexpr uint8_t MESSAGE_VERSION = 0;
359 
360  /** Measurement timestamps, if available. See @ref measurement_messages. */
362 
363  /**
364  * The front left wheel ticks. The interpretation of these ticks is
365  * defined outside of this message.
366  */
368 
369  /**
370  * The front right wheel ticks. The interpretation of these ticks is
371  * defined outside of this message.
372  */
374 
375  /**
376  * The rear left wheel ticks. The interpretation of these ticks is
377  * defined outside of this message.
378  */
379  uint32_t rear_left_wheel_ticks = 0;
380 
381  /**
382  * The rear right wheel ticks. The interpretation of these ticks is
383  * defined outside of this message.
384  */
386 
387  /**
388  * The transmission gear currently in use, or direction of motion, if
389  * available.
390  *
391  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
392  * direction information is available externally.
393  */
395 
396  uint8_t reserved[3] = {0};
397 };
398 
399 /**
400  * @brief Singular wheel encoder tick measurement, representing vehicle body
401  * speed (@ref MessageType::VEHICLE_TICK_MEASUREMENT, version 1.0).
402  * @ingroup measurement_messages
403  *
404  * This message may be used to convey a single encoder tick count received by
405  * software (e.g., vehicle CAN bus), or captured in hardware from an external
406  * voltage pulse, which represents the along-track speed of the vehicle
407  * (forward/backward). The interpretation of the tick count values varies by
408  * vehicle. To use wheel encoder data, you ust first configure the device by
409  * issuing a @ref SetConfigMessage message containing either a @ref WheelConfig
410  * or @ref HardwareTickConfig payload describing the vehicle sensor
411  * configuration.
412  *
413  * Some platforms may support an additional, optional voltage signal used to
414  * indicate direction of motion. Alternatively, when receiving CAN data from a
415  * vehicle, direction may be conveyed explicitly in a CAN message, or may be
416  * indicated based on the current transmission gear setting.
417  */
418 struct alignas(4) VehicleTickMeasurement : public MessagePayload {
419  static constexpr MessageType MESSAGE_TYPE =
421  static constexpr uint8_t MESSAGE_VERSION = 0;
422 
423  /** Measurement timestamps, if available. See @ref measurement_messages. */
425 
426  /**
427  * The current encoder tick count. The interpretation of these ticks is
428  * defined outside of this message.
429  */
430  uint32_t tick_count = 0;
431 
432  /**
433  * The transmission gear currently in use, or direction of motion, if
434  * available.
435  *
436  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
437  * direction information is available externally.
438  */
440 
441  uint8_t reserved[3] = {0};
442 };
443 
444 /**
445  * @brief The heading angle (in degrees) with respect to true north,
446  * pointing from the primary antenna to the secondary antenna (@ref
447  MessageType::HEADING_MEASUREMENT, version 1.0).
448  * @ingroup solution_messages
449  *
450  * @note
451  * All data is timestamped using the Point One Time, which is a monotonic
452  * timestamp referenced to the start of the device. Corresponding messages (@ref
453  * PoseMessage, @ref GNSSSatelliteMessage, etc.) may be associated using
454  * their @ref timestamps.
455  */
456 struct alignas(4) HeadingMeasurement : public MessagePayload {
458  static constexpr uint8_t MESSAGE_VERSION = 0;
459 
460  /** Measurement timestamps, if available. See @ref measurement_messages. */
462 
463  /** The type of this position solution. */
465 
466  uint8_t reserved[3] = {0};
467 
468  /** A bitmask of flags associated with the solution. */
469  uint32_t flags = 0;
470 
471  /**
472  * Position is measured with respect to the primary antenna as follows:
473  * @f[
474  * \Delta r_{ENU} = C^{ENU}_{ECEF} (r_{Secondary, ECEF} - r_{Primary, ECEF})
475  * @f]
476  *
477  * @note
478  * If a differential solution to the secondary antenna is not available, these
479  * values will be `NAN`.
480  */
481  float relative_position_enu_m[3] = {NAN, NAN, NAN};
482 
483  /**
484  * The position standard deviation (in meters), resolved with respect to the
485  * local ENU tangent plane: east, north, up.
486  *
487  * @note
488  * If a differential solution to the secondary antenna is not available, these
489  * values will be `NAN`.
490  */
491  float position_std_enu_m[3] = {NAN, NAN, NAN};
492 
493  /**
494  * The heading angle (in degrees) with respect to true north, pointing from
495  * the primary antenna to the secondary antenna.
496  *
497  * @note
498  * Reported in the range [0, 360).
499  */
501 
502  /**
503  * The estimated distance between primary and secondary antennas (in meters).
504  */
505  float baseline_distance_m = NAN;
506 };
507 
508 #pragma pack(pop)
509 
510 } // namespace messages
511 } // namespace fusion_engine
512 } // namespace point_one
static constexpr MessageType MESSAGE_TYPE
Definition: measurements.h:309
@ GPS_TIME
Message timestamped in GPS time, referenced to 1980/1/6.
SystemTimeSource
The source of a point_one::fusion_engine::messages::Timestamp used to represent the time of applicabi...
Definition: measurements.h:35
static constexpr uint8_t MESSAGE_VERSION
Definition: measurements.h:311
static constexpr uint8_t MESSAGE_VERSION
Definition: measurements.h:258
static constexpr MessageType MESSAGE_TYPE
Definition: measurements.h:160
MessageType
Identifiers for the defined output message types.
Definition: defs.h:35
Library portability helper definitions.
@ INVALID
Timestamp not valid.
SolutionType
Navigation solution type definitions.
Definition: defs.h:356
MeasurementTimestamps timestamps
Measurement timestamps, if available.
Definition: measurements.h:461
SystemTimeSource measurement_time_source
The source for measurement_time.
Definition: measurements.h:131
GearType gear
The transmission gear currently in use, or direction of motion, if available.
Definition: measurements.h:282
Differential wheel speed measurement (MessageType::WHEEL_SPEED_MEASUREMENT, version 1....
Definition: measurements.h:255
static constexpr MessageType MESSAGE_TYPE
Definition: measurements.h:419
@ TIMESTAMPED_ON_RECEPTION
Message timestamped in system time, generated when received by the device.
@ VEHICLE_TICK_MEASUREMENT
VehicleTickMeasurement
@ VEHICLE_SPEED_MEASUREMENT
VehicleSpeedMeasurement
The time of applicability for an incoming sensor measurement.
Definition: measurements.h:119
double accel_std_mps2[3]
Corrected vehicle x/y/z acceleration standard deviation (in meters/second^2), resolved in the body fr...
Definition: measurements.h:176
static constexpr MessageType MESSAGE_TYPE
Definition: measurements.h:356
@ NEUTRAL
The vehicle is in neutral.
float heading_true_north_deg
The heading angle (in degrees) with respect to true north, pointing from the primary antenna to the s...
Definition: measurements.h:500
MeasurementTimestamps timestamps
Measurement timestamps, if available.
Definition: measurements.h:361
Differential wheel encoder tick measurement (MessageType::WHEEL_TICK_MEASUREMENT, version 1....
Definition: measurements.h:355
float vehicle_speed_mps
The current vehicle speed estimate (in m/s).
Definition: measurements.h:317
The base class for all message payloads.
Definition: defs.h:540
IMU sensor measurement data (MessageType::IMU_MEASUREMENT, version 1.0).
Definition: measurements.h:159
The heading angle (in degrees) with respect to true north, pointing from the primary antenna to the s...
Definition: measurements.h:456
@ IMU_MEASUREMENT
IMUMeasurement
@ SENDER_SYSTEM_TIME
Message timestamp was generated from a monotonic clock of an external system.
@ WHEEL_SPEED_MEASUREMENT
WheelSpeedMeasurement
@ REVERSE
The vehicle is in reverse.
@ Invalid
Invalid, no position available.
double gyro_rps[3]
Corrected vehicle x/y/z rate of rotation (in radians/second), resolved in the body frame.
Definition: measurements.h:182
GNSS signal and frequency type definitions.
Definition: logging.h:36
Timestamp p1_time
The P1 time corresponding with the measurement time of applicability, if available.
Definition: measurements.h:146
MeasurementTimestamps timestamps
Measurement timestamps, if available.
Definition: measurements.h:314
static constexpr uint8_t MESSAGE_VERSION
Definition: measurements.h:358
static constexpr uint8_t MESSAGE_VERSION
Definition: measurements.h:458
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: measurements.h:164
GearType gear
The transmission gear currently in use, or direction of motion, if available.
Definition: measurements.h:394
float front_left_speed_mps
The front left wheel speed (in m/s).
Definition: measurements.h:264
P1_CONSTEXPR_FUNC const char * to_string(ConfigType type)
Get a human-friendly string name for the specified ConfigType.
SolutionType solution_type
The type of this position solution.
Definition: measurements.h:464
float front_right_speed_mps
The front right wheel speed (in m/s).
Definition: measurements.h:267
uint32_t rear_right_wheel_ticks
The rear right wheel ticks.
Definition: measurements.h:385
GearType
The current transmission gear used by the vehicle.
Definition: measurements.h:195
GearType gear
The transmission gear currently in use, or direction of motion, if available.
Definition: measurements.h:439
static constexpr MessageType MESSAGE_TYPE
Definition: measurements.h:457
float position_std_enu_m[3]
The position standard deviation (in meters), resolved with respect to the local ENU tangent plane: ea...
Definition: measurements.h:491
Timestamp measurement_time
The measurement time of applicability, if available, in a user-specified time base.
Definition: measurements.h:126
float rear_right_speed_mps
The rear right wheel speed (in m/s).
Definition: measurements.h:273
uint32_t tick_count
The current encoder tick count.
Definition: measurements.h:430
float rear_left_speed_mps
The rear left wheel speed (in m/s).
Definition: measurements.h:270
static constexpr MessageType MESSAGE_TYPE
Definition: measurements.h:256
@ WHEEL_TICK_MEASUREMENT
WheelTickMeasurement
#define P1_CONSTEXPR_FUNC
Definition: portability.h:58
static constexpr uint8_t MESSAGE_VERSION
Definition: measurements.h:161
bool is_signed
true if the wheel speeds are signed (positive forward, negative reverse), or false if the values are ...
Definition: measurements.h:288
float relative_position_enu_m[3]
Position is measured with respect to the primary antenna as follows:
Definition: measurements.h:481
MeasurementTimestamps timestamps
Measurement timestamps, if available.
Definition: measurements.h:261
Singular wheel encoder tick measurement, representing vehicle body speed (MessageType::VEHICLE_TICK_M...
Definition: measurements.h:418
uint32_t front_left_wheel_ticks
The front left wheel ticks.
Definition: measurements.h:367
Vehicle body speed measurement (MessageType::VEHICLE_SPEED_MEASUREMENT, version 1....
Definition: measurements.h:308
float baseline_distance_m
The estimated distance between primary and secondary antennas (in meters).
Definition: measurements.h:505
@ P1_TIME
Message timestamped in P1 time.
std::ostream & operator<<(std::ostream &stream, ConfigType type)
ConfigType stream operator.
@ FORWARD
The vehicle is in a forward gear.
Point One FusionEngine output message common definitions.
@ PARK
The vehicle is parked.
uint32_t flags
A bitmask of flags associated with the solution.
Definition: measurements.h:469
@ HEADING_MEASUREMENT
HeadingMeasurement
Generic timestamp representation.
Definition: defs.h:441
uint32_t rear_left_wheel_ticks
The rear left wheel ticks.
Definition: measurements.h:379
double accel_mps2[3]
Corrected vehicle x/y/z acceleration (in meters/second^2), resolved in the body frame.
Definition: measurements.h:170
GearType gear
The transmission gear currently in use, or direction of motion, if available.
Definition: measurements.h:326
double gyro_std_rps[3]
Corrected vehicle x/y/z rate of rotation standard deviation (in radians/second), resolved in the body...
Definition: measurements.h:188
bool is_signed
true if the wheel speeds are signed (positive forward, negative reverse), or false if the values are ...
Definition: measurements.h:332
@ UNKNOWN
The transmission gear is not known, or does not map to a supported GearType.
MeasurementTimestamps timestamps
Measurement timestamps, if available.
Definition: measurements.h:424
static constexpr uint8_t MESSAGE_VERSION
Definition: measurements.h:421
uint32_t front_right_wheel_ticks
The front right wheel ticks.
Definition: measurements.h:373