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 received sensor measurements, if known.
31  * @ingroup measurement_messages
32  */
33 enum class SensorDataSource : uint8_t {
34  /** Data source not known. */
35  UNKNOWN = 0,
36  /**
37  * Sensor data captured internal to the device (embedded IMU, GNSS receiver,
38  * etc.).
39  */
40  INTERNAL = 1,
41  /**
42  * Sensor data generated via hardware voltage signal (wheel tick, external
43  * event, etc.).
44  */
45  HARDWARE_IO = 2,
46  /** Sensor data captured from a vehicle CAN bus. */
47  CAN = 3,
48  /** Sensor data provided over a serial connection. */
49  SERIAL = 4,
50  /** Sensor data provided over a network connection. */
51  NETWORK = 5,
52 };
53 
54 /**
55  * @brief Get a human-friendly string name for the specified @ref
56  * SensorDataSource.
57  * @ingroup measurement_messages
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 "Unknown";
68  return "Internal";
70  return "Hardware I/O";
72  return "CAN";
74  return "Serial";
76  return "Network";
77  }
78  return "Unrecognized";
79 }
80 
81 /**
82  * @brief @ref SensorDataSource stream operator.
83  * @ingroup measurement_messages
84  */
86  stream << to_string(val) << " (" << (int)val << ")";
87  return stream;
88 }
89 
90 /**
91  * @brief The source of a @ref point_one::fusion_engine::messages::Timestamp
92  * used to represent the time of applicability of an incoming sensor
93  * measurement.
94  * @ingroup measurement_messages
95  */
96 enum class SystemTimeSource : uint8_t {
97  /** Timestamp not valid. */
98  INVALID = 0,
99  /** Message timestamped in P1 time. */
100  P1_TIME = 1,
101  /**
102  * Message timestamped in system time, generated when received by the device.
103  */
105  /**
106  * Message timestamp was generated from a monotonic clock of an external
107  * system.
108  */
109  SENDER_SYSTEM_TIME = 3,
110  /**
111  * Message timestamped in GPS time, referenced to 1980/1/6.
112  */
113  GPS_TIME = 4,
114 };
115 
116 /**
117  * @brief Get a human-friendly string name for the specified @ref
118  * SystemTimeSource.
119  * @ingroup measurement_messages
120  *
121  * @param val The enum to get the string name for.
122  *
123  * @return The corresponding string name.
124  */
126  switch (val) {
128  return "Invalid";
130  return "P1 Time";
132  return "Timestamped on Reception";
134  return "Sender System Time";
136  return "GPS Time";
137  }
138  return "Unrecognized";
139 }
140 
141 /**
142  * @brief @ref SystemTimeSource stream operator.
143  * @ingroup measurement_messages
144  */
146  stream << to_string(val) << " (" << (int)val << ")";
147  return stream;
148 }
149 
150 /**
151  * @brief The time of applicability and additional information for an incoming
152  * sensor measurement.
153  * @ingroup measurement_messages
154  *
155  * By convention this will be the first member of any message containing
156  * input measurements by the host to the device, as well as raw measurement
157  * outputs from the device.
158  *
159  * The @ref measurement_time field stores time of applicability/reception for
160  * the measurement data, expressed in one of the available source time bases
161  * (see @ref SystemTimeSource). The timestamp will be converted to P1 time
162  * automatically by FusionEngine using an internal model of P1 vs. the specified
163  * source time.
164  *
165  * @section meas_details_on_arrival Timestamp On Arrival
166  *
167  * On most platforms, incoming sensor measurements are timestamped automatically
168  * by FusionEngine when they arrive. To request timestamp on arrival, set @ref
169  * measurement_time_source to either @ref
170  * SystemTimeSource::TIMESTAMPED_ON_RECEPTION or @ref SystemTimeSource::INVALID.
171  *
172  * @section meas_details_external_time Timestamp Externally
173  *
174  * On some platforms, incoming sensor measurements may be timestamped
175  * externally by the host prior to arrival, either in GPS time (@ref
176  * SystemTimeSource::GPS_TIME), or using a monotonic clock controlled by the
177  * host system (@ref SystemTimeSource::SENDER_SYSTEM_TIME). For those platforms,
178  * the @ref measurement_time field should be specified in the incoming message.
179  *
180  * @note
181  * Use of an external monotonic clock requires additional coordination with the
182  * target FusionEngine device.
183  *
184  * @section meas_details_p1_time Timestamp With External P1 Time
185  *
186  * Measurements may only be timestamped externally using P1 time (@ref
187  * SystemTimeSource::P1_TIME) if the external system supports remote
188  * synchronization of the P1 time clock model. This is intended for internal
189  * use only.
190  */
192  /**
193  * The measurement time of applicability, if available, in a user-specified
194  * time base. The source of this value is specified in @ref
195  * measurement_time_source. The timestamp will be converted to P1 time
196  * internally by the device before use.
197  */
199 
200  /**
201  * The source for @ref measurement_time.
202  */
203  SystemTimeSource measurement_time_source = SystemTimeSource::INVALID;
204 
205  /**
206  * The source of the incoming data, if known.
207  */
209 
210  uint8_t reserved[2] = {0};
211 
212  /**
213  * The P1 time corresponding with the measurement time of applicability, if
214  * available.
215  *
216  * For inputs to the device, this field will be populated automatically by the
217  * device on arrival based on @ref measurement_time. Any existing value will
218  * be overwritten. To specify a known P1 time, specify the value in @ref
219  * measurement_time and set @ref measurement_time_source to @ref
220  * SystemTimeSource::P1_TIME.
221  *
222  * For outputs from the device, this field will always be populated with the
223  * P1 time corresponding with the measurement.
224  */
226 };
227 
228 ////////////////////////////////////////////////////////////////////////////////
229 // IMU Measurements
230 ////////////////////////////////////////////////////////////////////////////////
231 
232 /**
233  * @brief IMU sensor measurement input (@ref MessageType::IMU_INPUT,
234  * version 1.0).
235  * @ingroup measurement_messages
236  *
237  * This message is an input to the device containing raw IMU acceleration and
238  * rotation rate measurements.
239  *
240  * See also @ref IMUOutput.
241  */
242 struct P1_ALIGNAS(4) IMUInput : public MessagePayload {
243  static constexpr MessageType MESSAGE_TYPE = MessageType::IMU_INPUT;
244  static constexpr uint8_t MESSAGE_VERSION = 0;
245 
246  /**
247  * Measurement timestamp and additional information, if available. See @ref
248  * MeasurementDetails for details.
249  */
251 
252  uint8_t reserved[6] = {0};
253 
254  /**
255  * The IMU temperature (in deg Celsius * 2^-7). Set to 0x7FFF if invalid.
256  */
257  int16_t temperature = INT16_MAX;
258 
259  /**
260  * Measured x/y/z acceleration (in meters/second^2 * 2^-16), resolved in the
261  * sensor measurement frame. Set to 0x7FFFFFFF if invalid.
262  */
263  int32_t accel[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
264 
265  /**
266  * Measured x/y/z rate of rotation (in radians/second * 2^-20), resolved in
267  * the sensor measurement frame. Set to 0x7FFFFFFF if invalid.
268  */
269  int32_t gyro[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
270 };
271 
272 /**
273  * @brief IMU sensor measurement output with calibration and corrections applied
274  * (@ref MessageType::IMU_OUTPUT, version 1.0).
275  * @ingroup measurement_messages
276  *
277  * This message is an output from the device containing IMU acceleration and
278  * rotation rate measurements. The measurements been corrected for biases and
279  * scale factors, and have been rotated into the vehicle body frame from the
280  * original IMU orientation, including calibrated mounting error estimates.
281  *
282  * See also @ref RawIMUOutput.
283  */
284 struct P1_ALIGNAS(4) IMUOutput : public MessagePayload {
285  static constexpr MessageType MESSAGE_TYPE = MessageType::IMU_OUTPUT;
286  static constexpr uint8_t MESSAGE_VERSION = 0;
287 
288  /** The time of the measurement, in P1 time (beginning at power-on). */
290 
291  /**
292  * Corrected vehicle x/y/z acceleration (in meters/second^2), resolved in the
293  * body frame.
294  */
295  double accel_mps2[3] = {NAN, NAN, NAN};
296 
297  /**
298  * Corrected vehicle x/y/z acceleration standard deviation (in
299  * meters/second^2), resolved in the body frame.
300  */
301  double accel_std_mps2[3] = {NAN, NAN, NAN};
302 
303  /**
304  * Corrected vehicle x/y/z rate of rotation (in radians/second), resolved in
305  * the body frame.
306  */
307  double gyro_rps[3] = {NAN, NAN, NAN};
308 
309  /**
310  * Corrected vehicle x/y/z rate of rotation standard deviation (in
311  * radians/second), resolved in the body frame.
312  */
313  double gyro_std_rps[3] = {NAN, NAN, NAN};
314 };
315 
316 /**
317  * @brief Raw (uncorrected) IMU sensor measurement output (@ref
318  MessageType::RAW_IMU_OUTPUT, version 1.0).
319  * @ingroup measurement_messages
320  *
321  * This message is an output from the device containing raw IMU acceleration and
322  * rotation rate measurements. These measurements come directly from the sensor,
323  * and do not have any corrections or calibration applied.
324  *
325  * See also @ref IMUOutput.
326  */
328  static constexpr MessageType MESSAGE_TYPE = MessageType::RAW_IMU_OUTPUT;
329  static constexpr uint8_t MESSAGE_VERSION = 0;
330 
331  /**
332  * Measurement timestamp and additional information, if available. See @ref
333  * MeasurementDetails for details.
334  */
336 
337  uint8_t reserved[6] = {0};
338 
339  /**
340  * The IMU temperature (in deg Celsius * 2^-7). Set to 0x7FFF if invalid.
341  */
342  int16_t temperature = INT16_MAX;
343 
344  /**
345  * Measured x/y/z acceleration (in meters/second^2 * 2^-16), resolved in the
346  * sensor measurement frame. Set to 0x7FFFFFFF if invalid.
347  */
348  int32_t accel[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
349 
350  /**
351  * Measured x/y/z rate of rotation (in radians/second * 2^-20), resolved in
352  * the sensor measurement frame. Set to 0x7FFFFFFF if invalid.
353  */
354  int32_t gyro[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
355 };
356 
357 ////////////////////////////////////////////////////////////////////////////////
358 // Different Wheel Speed Measurements
359 ////////////////////////////////////////////////////////////////////////////////
360 
361 /**
362  * @brief The current transmission gear used by the vehicle.
363  * @ingroup measurement_messages
364  */
365 enum class GearType : uint8_t {
366  /**
367  * The transmission gear is not known, or does not map to a supported
368  * GearType.
369  */
370  UNKNOWN = 0,
371  FORWARD = 1, ///< The vehicle is in a forward gear.
372  REVERSE = 2, ///< The vehicle is in reverse.
373  PARK = 3, ///< The vehicle is parked.
374  NEUTRAL = 4, ///< The vehicle is in neutral.
375 };
376 
377 /**
378  * @brief Get a human-friendly string name for the specified @ref GearType.
379  * @ingroup measurement_messages
380  *
381  * @param val The enum to get the string name for.
382  *
383  * @return The corresponding string name.
384  */
386  switch (val) {
387  case GearType::UNKNOWN:
388  return "Unknown";
389  case GearType::FORWARD:
390  return "Forward";
391  case GearType::REVERSE:
392  return "Reverse";
393  case GearType::PARK:
394  return "Park";
395  case GearType::NEUTRAL:
396  return "Neutral";
397  }
398  return "Unrecognized";
399 }
400 
401 /**
402  * @brief @ref GearType stream operator.
403  * @ingroup measurement_messages
404  */
405 inline p1_ostream& operator<<(p1_ostream& stream, GearType val) {
406  stream << to_string(val) << " (" << (int)val << ")";
407  return stream;
408 }
409 
410 /**
411  * @brief Differential wheel speed measurement input (@ref
412  * MessageType::WHEEL_SPEED_INPUT, version 1.0).
413  * @ingroup measurement_messages
414  *
415  * This message is an input to the device, used to convey the speed of each
416  * individual wheel on the vehicle. The number and type of wheels expected
417  * varies by vehicle. For single along-track speed measurements, see @ref
418  * VehicleSpeedInput.
419  *
420  * To use wheel speed data, you must first configure the device by issuing a
421  * @ref SetConfigMessage message containing a @ref WheelConfig payload
422  * describing the vehicle sensor configuration (speed data signed/unsigned,
423  * etc.).
424  *
425  * Some platforms may have an additional signal used to indicate direction of
426  * motion, have direction or gear information available from a vehicle CAN bus,
427  * etc. If direction/gear information is available, it may be provided in the
428  * @ref gear field.
429  *
430  * To send wheel tick counts from software, use @ref WheelTickInput instead.
431  *
432  * See also @ref WheelSpeedOutput for measurement output.
433  */
435  static constexpr MessageType MESSAGE_TYPE = MessageType::WHEEL_SPEED_INPUT;
436  static constexpr uint8_t MESSAGE_VERSION = 0;
437 
438  /**
439  * Set this flag if the measured wheel speeds are signed (positive forward,
440  * negative reverse). Otherwise, if the values are assumed to be unsigned
441  * (positive in both directions).
442  */
443  static constexpr uint8_t FLAG_SIGNED = 0x1;
444 
445  /**
446  * Measurement timestamp and additional information, if available. See @ref
447  * MeasurementDetails for details.
448  */
450 
451  /**
452  * The front left wheel speed (in m/s * 2^-10). Set to 0x7FFFFFFF if not
453  * available.
454  */
455  int32_t front_left_speed = INT32_MAX;
456 
457  /**
458  * The front right wheel speed (in m/s * 2^-10). Set to 0x7FFFFFFF if not
459  * available.
460  */
461  int32_t front_right_speed = INT32_MAX;
462 
463  /**
464  * The rear left wheel speed (in m/s * 2^-10). Set to 0x7FFFFFFF if not
465  * available.
466  */
467  int32_t rear_left_speed = INT32_MAX;
468 
469  /**
470  * The rear right wheel speed (in m/s * 2^-10). Set to 0x7FFFFFFF if not
471  * available.
472  */
473  int32_t rear_right_speed = INT32_MAX;
474 
475  /**
476  * The transmission gear currently in use, or direction of motion, if
477  * available.
478  *
479  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
480  * direction information is available externally.
481  */
483 
484  /** A bitmask of flags associated with the measurement data. */
485  uint8_t flags = 0x0;
486 
487  uint8_t reserved[2] = {0};
488 };
489 
490 /**
491  * @brief Differential wheel speed measurement output with calibration and
492  * corrections applied (@ref MessageType::WHEEL_SPEED_OUTPUT, version
493  1.0).
494  * @ingroup measurement_messages
495  *
496  * This message is an output from the device that contains the speed of each
497  * individual wheel on the vehicle, after applying any estimated corrections for
498  * wheel scale factor, sign, etc.
499  *
500  * Wheel odometry data may be received via a software input from a host machine,
501  * a vehicle CAN bus, or a hardware voltage signal (wheel ticks). The @ref
502  * data_source field will indicate which type of data source provided the
503  * measurements to the device.
504  *
505  * @note
506  * When odometry is provided using hardware wheel ticks, the output rate of this
507  * message may differ from the wheel tick input rate. For high accuracy
508  * applications, FusionEngine may integrate tick counts over longer intervals to
509  * improve performance.
510  *
511  * See also @ref WheelSpeedInput and @ref RawWheelSpeedOutput.
512  */
514  static constexpr MessageType MESSAGE_TYPE = MessageType::WHEEL_SPEED_OUTPUT;
515  static constexpr uint8_t MESSAGE_VERSION = 0;
516 
517  /**
518  * Set this flag if the measured wheel speeds are signed (positive forward,
519  * negative reverse). Otherwise, if the values are assumed to be unsigned
520  * (positive in both directions).
521  */
522  static constexpr uint8_t FLAG_SIGNED = 0x1;
523 
524  /** The time of the measurement, in P1 time (beginning at power-on). */
526 
527  /**
528  * The source of the incoming data, if known.
529  */
531 
532  /**
533  * The transmission gear currently in use, or direction of motion, if
534  * available.
535  */
537 
538  /** A bitmask of flags associated with the measurement data. */
539  uint8_t flags = 0x0;
540 
541  uint8_t reserved = 0;
542 
543  /** The front left wheel speed (in m/s). Set to NAN if not available. */
544  float front_left_speed_mps = NAN;
545 
546  /** The front right wheel speed (in m/s). Set to NAN if not available. */
547  float front_right_speed_mps = NAN;
548 
549  /** The rear left wheel speed (in m/s). Set to NAN if not available. */
550  float rear_left_speed_mps = NAN;
551 
552  /** The rear right wheel speed (in m/s). Set to NAN if not available. */
553  float rear_right_speed_mps = NAN;
554 };
555 
556 /**
557  * @brief Raw (uncorrected) dfferential wheel speed measurement output (@ref
558  * MessageType::RAW_WHEEL_SPEED_OUTPUT, version 1.0).
559  * @ingroup measurement_messages
560  *
561  * This message is an output from the device that contains the speed of each
562  * individual wheel on the vehicle. These measurements come directly from the
563  * sensor, and do not have any corrections or calibration applied.
564  *
565  * See @ref WheelSpeedOutput for more details. See also @ref WheelSpeedInput.
566  */
568  static constexpr MessageType MESSAGE_TYPE =
570  static constexpr uint8_t MESSAGE_VERSION = 0;
571 
572  /**
573  * Set this flag if the measured wheel speeds are signed (positive forward,
574  * negative reverse). Otherwise, if the values are assumed to be unsigned
575  * (positive in both directions).
576  */
577  static constexpr uint8_t FLAG_SIGNED = 0x1;
578 
579  /**
580  * Measurement timestamp and additional information, if available. See @ref
581  * MeasurementDetails for details.
582  */
584 
585  /**
586  * The front left wheel speed (in m/s * 2^-10). Set to 0x7FFFFFFF if not
587  * available.
588  */
589  int32_t front_left_speed = INT32_MAX;
590 
591  /**
592  * The front right wheel speed (in m/s * 2^-10). Set to 0x7FFFFFFF if not
593  * available.
594  */
595  int32_t front_right_speed = INT32_MAX;
596 
597  /**
598  * The rear left wheel speed (in m/s * 2^-10). Set to 0x7FFFFFFF if not
599  * available.
600  */
601  int32_t rear_left_speed = INT32_MAX;
602 
603  /**
604  * The rear right wheel speed (in m/s * 2^-10). Set to 0x7FFFFFFF if not
605  * available.
606  */
607  int32_t rear_right_speed = INT32_MAX;
608 
609  /**
610  * The transmission gear currently in use, or direction of motion, if
611  * available.
612  *
613  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
614  * direction information is available externally.
615  */
617 
618  /** A bitmask of flags associated with the measurement data. */
619  uint8_t flags = 0x0;
620 
621  uint8_t reserved[2] = {0};
622 };
623 
624 ////////////////////////////////////////////////////////////////////////////////
625 // Vehicle Speed Measurements
626 ////////////////////////////////////////////////////////////////////////////////
627 
628 /**
629  * @brief Vehicle body speed measurement input (@ref
630  * MessageType::VEHICLE_SPEED_INPUT, version 1.0).
631  * @ingroup measurement_messages
632  *
633  * This message is an input to the device, used to convey the along-track speed
634  * of the vehicle (forward/backward). For differential speed measurements for
635  * multiple wheels, see @ref WheelSpeedInput.
636  *
637  * To use vehicle speed data, you must first configure the device by issuing a
638  * @ref SetConfigMessage message containing a @ref WheelConfig payload
639  * describing the vehicle sensor configuration (speed data signed/unsigned,
640  * etc.).
641  *
642  * Some platforms may have an additional signal used to indicate direction of
643  * motion, have direction or gear information available from a vehicle CAN bus,
644  * etc. If direction/gear information is available, it may be provided in the
645  * @ref gear field.
646  *
647  * To send wheel tick counts from software, use @ref VehicleTickInput instead.
648  *
649  * See also @ref VehicleSpeedOutput for measurement output.
650  */
652  static constexpr MessageType MESSAGE_TYPE = MessageType::VEHICLE_SPEED_INPUT;
653  static constexpr uint8_t MESSAGE_VERSION = 0;
654 
655  /**
656  * Set this flag if the measured wheel speeds are signed (positive forward,
657  * negative reverse). Otherwise, if the values are assumed to be unsigned
658  * (positive in both directions).
659  */
660  static constexpr uint8_t FLAG_SIGNED = 0x1;
661 
662  /**
663  * Measurement timestamp and additional information, if available. See @ref
664  * MeasurementDetails for details.
665  */
667 
668  /**
669  * The current vehicle speed estimate (in m/s * 2^-10). Set to 0x7FFFFFFF if
670  * not available.
671  */
672  int32_t vehicle_speed = INT32_MAX;
673 
674  /**
675  * The transmission gear currently in use, or direction of motion, if
676  * available.
677  *
678  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
679  * direction information is available externally.
680  */
682 
683  /** A bitmask of flags associated with the measurement data. */
684  uint8_t flags = 0x0;
685 
686  uint8_t reserved[2] = {0};
687 };
688 
689 /**
690  * @brief Vehicle body speed measurement output with calibration and corrections
691  * applied (@ref MessageType::VEHICLE_SPEED_OUTPUT, version 1.0).
692  * @ingroup measurement_messages
693  *
694  * This message is an output from the device that contains the along-track speed
695  * of the vehicle (forward/backward), after applying any estimated corrections
696  * for scale factor, etc.
697  *
698  * Odometry data may be received via a software input from a host machine, a
699  * vehicle CAN bus, or a hardware voltage signal (wheel ticks). The @ref
700  * data_source field will indicate which type of data source provided the
701  * measurements to the device.
702  *
703  * @note
704  * When odometry is provided using hardware wheel ticks, the output rate of this
705  * message may differ from the wheel tick input rate. For high accuracy
706  * applications, FusionEngine may integrate tick counts over longer intervals to
707  * improve performance.
708  *
709  * See also @ref VehicleSpeedInput and @ref RawVehicleSpeedOutput.
710  */
712  static constexpr MessageType MESSAGE_TYPE = MessageType::VEHICLE_SPEED_OUTPUT;
713  static constexpr uint8_t MESSAGE_VERSION = 0;
714 
715  /**
716  * Set this flag if the measured wheel speeds are signed (positive forward,
717  * negative reverse). Otherwise, if the values are assumed to be unsigned
718  * (positive in both directions).
719  */
720  static constexpr uint8_t FLAG_SIGNED = 0x1;
721 
722  /** The time of the measurement, in P1 time (beginning at power-on). */
724 
725  /**
726  * The source of the incoming data, if known.
727  */
729 
730  /**
731  * The transmission gear currently in use, or direction of motion, if
732  * available.
733  *
734  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
735  * direction information is available externally.
736  */
738 
739  /** A bitmask of flags associated with the measurement data. */
740  uint8_t flags = 0x0;
741 
742  uint8_t reserved = 0;
743 
744  /** The current vehicle speed estimate (in m/s). */
745  float vehicle_speed_mps = NAN;
746 };
747 
748 /**
749  * @brief Raw (uncorrected) vehicle body speed measurement output (@ref
750  * MessageType::RAW_VEHICLE_SPEED_OUTPUT, version 1.0).
751  * @ingroup measurement_messages
752  *
753  * This message is an output from the device that contains the along-track speed
754  * of the vehicle (forward/backward). These measurements come directly from the
755  * sensor, and do not have any corrections or calibration applied.
756  *
757  * See @ref VehicleSpeedOutput for more details. See also @ref
758  * VehicleSpeedInput.
759  */
761  static constexpr MessageType MESSAGE_TYPE =
763  static constexpr uint8_t MESSAGE_VERSION = 0;
764 
765  /**
766  * Set this flag if the measured wheel speeds are signed (positive forward,
767  * negative reverse). Otherwise, if the values are assumed to be unsigned
768  * (positive in both directions).
769  */
770  static constexpr uint8_t FLAG_SIGNED = 0x1;
771 
772  /**
773  * Measurement timestamp and additional information, if available. See @ref
774  * MeasurementDetails for details.
775  */
777 
778  /**
779  * The current vehicle speed estimate (in m/s * 2^-10). Set to 0x7FFFFFFF if
780  * not available.
781  */
782  int32_t vehicle_speed = INT32_MAX;
783 
784  /**
785  * The transmission gear currently in use, or direction of motion, if
786  * available.
787  *
788  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
789  * direction information is available externally.
790  */
792 
793  /** A bitmask of flags associated with the measurement data. */
794  uint8_t flags = 0x0;
795 
796  uint8_t reserved[2] = {0};
797 };
798 
799 ////////////////////////////////////////////////////////////////////////////////
800 // Wheel Tick Measurements
801 ////////////////////////////////////////////////////////////////////////////////
802 
803 /**
804  * @brief Differential wheel encoder tick input (@ref
805  * MessageType::WHEEL_TICK_INPUT, version 1.0).
806  * @ingroup measurement_messages
807  *
808  * This message is an input to the device, used to convey the wheel encoder tick
809  * counts for one or more wheels. The number and type of wheels expected, and
810  * the interpretation of the tick count values, varies by vehicle.
811  *
812  * To use wheel encoder data, you must first configure the device by issuing a
813  * @ref SetConfigMessage message containing a @ref WheelConfig payload
814  * describing the vehicle sensor configuration (tick counts signed/unsigned,
815  * etc.).
816  *
817  * Some platforms may have an additional signal used to indicate direction of
818  * motion, have direction or gear information available from a vehicle CAN bus,
819  * etc. If direction/gear information is available, it may be provided in the
820  * @ref gear field.
821  *
822  * See also @ref RawWheelTickOutput for measurement output.
823  */
825  static constexpr MessageType MESSAGE_TYPE = MessageType::WHEEL_TICK_INPUT;
826  static constexpr uint8_t MESSAGE_VERSION = 0;
827 
828  /**
829  * Measurement timestamp and additional information, if available. See @ref
830  * MeasurementDetails for details.
831  */
833 
834  /**
835  * The front left wheel ticks. The interpretation of these ticks is
836  * defined outside of this message.
837  */
838  uint32_t front_left_wheel_ticks = 0;
839 
840  /**
841  * The front right wheel ticks. The interpretation of these ticks is
842  * defined outside of this message.
843  */
844  uint32_t front_right_wheel_ticks = 0;
845 
846  /**
847  * The rear left wheel ticks. The interpretation of these ticks is
848  * defined outside of this message.
849  */
850  uint32_t rear_left_wheel_ticks = 0;
851 
852  /**
853  * The rear right wheel ticks. The interpretation of these ticks is
854  * defined outside of this message.
855  */
856  uint32_t rear_right_wheel_ticks = 0;
857 
858  /**
859  * The transmission gear currently in use, or direction of motion, if
860  * available.
861  *
862  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
863  * direction information is available externally.
864  */
866 
867  uint8_t reserved[3] = {0};
868 };
869 
870 /**
871  * @brief Raw (uncorrected) dfferential wheel encoder tick output (@ref
872  * MessageType::RAW_WHEEL_TICK_OUTPUT, version 1.0).
873  * @ingroup measurement_messages
874  *
875  * This message is an output from the device that contains wheel encoder tick
876  * counts for each individual wheel on the vehicle. Wheel ticks may be captured
877  * in hardware from an external voltage pulse, conveyed via software using a
878  * @ref WheelTickInput message, or decoded from a vehicle CAN bus. The number
879  * and type of wheels expected, and the interpretation of the tick count values,
880  * varies by vehicle.
881  *
882  * These measurements come directly from the sensor, and do not have any
883  * corrections or calibration applied.
884  *
885  * See also @ref WheelTickInput.
886  */
888  static constexpr MessageType MESSAGE_TYPE =
890  static constexpr uint8_t MESSAGE_VERSION = 0;
891 
892  /**
893  * Measurement timestamp and additional information, if available. See @ref
894  * MeasurementDetails for details.
895  */
897 
898  /**
899  * The front left wheel ticks. The interpretation of these ticks is
900  * defined outside of this message.
901  */
902  uint32_t front_left_wheel_ticks = 0;
903 
904  /**
905  * The front right wheel ticks. The interpretation of these ticks is
906  * defined outside of this message.
907  */
908  uint32_t front_right_wheel_ticks = 0;
909 
910  /**
911  * The rear left wheel ticks. The interpretation of these ticks is
912  * defined outside of this message.
913  */
914  uint32_t rear_left_wheel_ticks = 0;
915 
916  /**
917  * The rear right wheel ticks. The interpretation of these ticks is
918  * defined outside of this message.
919  */
920  uint32_t rear_right_wheel_ticks = 0;
921 
922  /**
923  * The transmission gear currently in use, or direction of motion, if
924  * available.
925  *
926  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
927  * direction information is available externally.
928  */
930 
931  uint8_t reserved[3] = {0};
932 };
933 
934 ////////////////////////////////////////////////////////////////////////////////
935 // Vehicle Tick Measurements
936 ////////////////////////////////////////////////////////////////////////////////
937 
938 /**
939  * @brief Single wheel encoder tick input, representing vehicle body speed
940  * (@ref MessageType::VEHICLE_TICK_INPUT, version 1.0).
941  * @ingroup measurement_messages
942  *
943  * This message is an input to the device, used to convey a single wheel encoder
944  * tick count representing the along-track speed of the vehicle
945  * (forward/backward). The interpretation of the tick count values varies by
946  * vehicle.
947  *
948  * To use wheel encoder data, you must first configure the device by issuing a
949  * @ref SetConfigMessage message containing either a @ref WheelConfig payload
950  * describing the vehicle sensor configuration (tick counts signed/unsigned,
951  * etc.). Note that you should _not_ use the @ref HardwareTickConfig payload,
952  * which is used when configuring the device to capture a wheel tick voltage
953  * signal in hardware.
954  *
955  * Some platforms may have an additional signal used to indicate direction of
956  * motion, have direction or gear information available from a vehicle CAN bus,
957  * etc. If direction/gear information is available, it may be provided in the
958  * @ref gear field.
959  *
960  * See also @ref RawVehicleTickOutput for measurement output.
961  */
963  static constexpr MessageType MESSAGE_TYPE = MessageType::VEHICLE_TICK_INPUT;
964  static constexpr uint8_t MESSAGE_VERSION = 0;
965 
966  /**
967  * Measurement timestamp and additional information, if available. See @ref
968  * MeasurementDetails for details.
969  */
971 
972  /**
973  * The current encoder tick count. The interpretation of these ticks is
974  * defined outside of this message.
975  */
976  uint32_t tick_count = 0;
977 
978  /**
979  * The transmission gear currently in use, or direction of motion, if
980  * available.
981  *
982  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
983  * direction information is available externally.
984  */
986 
987  uint8_t reserved[3] = {0};
988 };
989 
990 /**
991  * @brief Raw (uncorrected) single wheel encoder tick output (@ref
992  * MessageType::RAW_VEHICLE_TICK_OUTPUT, version 1.0).
993  * @ingroup measurement_messages
994  *
995  * This message is an output from the device that contains a wheel encoder tick
996  * count representing the along-track speed of the vehicle (forward/backward).
997  * Wheel ticks may be captured in hardware from an external voltage pulse,
998  * conveyed via software using a @ref VehicleTickInput message, or decoded from
999  * a vehicle CAN bus. The interpretation of the tick count values varies by
1000  * vehicle.
1001  *
1002  * This value comes directly from the sensor, and does not have any corrections
1003  * or calibration applied.
1004  *
1005  * See also @ref VehicleTickInput.
1006  */
1008  static constexpr MessageType MESSAGE_TYPE =
1010  static constexpr uint8_t MESSAGE_VERSION = 0;
1011 
1012  /**
1013  * Measurement timestamp and additional information, if available. See @ref
1014  * MeasurementDetails for details.
1015  */
1017 
1018  /**
1019  * The current encoder tick count. The interpretation of these ticks is
1020  * defined outside of this message.
1021  */
1022  uint32_t tick_count = 0;
1023 
1024  /**
1025  * The transmission gear currently in use, or direction of motion, if
1026  * available.
1027  *
1028  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
1029  * direction information is available externally.
1030  */
1032 
1033  uint8_t reserved[3] = {0};
1034 };
1035 
1036 ////////////////////////////////////////////////////////////////////////////////
1037 // Deprecated Speed Measurement Definitions
1038 ////////////////////////////////////////////////////////////////////////////////
1039 
1040 /**
1041  * @brief (Deprecated) Differential wheel speed measurement (@ref
1042  * MessageType::DEPRECATED_WHEEL_SPEED_MEASUREMENT, version 1.0).
1043  * @ingroup measurement_messages
1044  *
1045  * @deprecated
1046  * This message is deprecated as of version 1.18.0 and may be removed in the
1047  * future. It should not used for new development. See @ref WheelSpeedInput and
1048  * @ref WheelSpeedOutput instead.
1049  */
1051  static constexpr MessageType MESSAGE_TYPE =
1053  static constexpr uint8_t MESSAGE_VERSION = 0;
1054 
1055  /**
1056  * Measurement timestamp and additional information, if available. See @ref
1057  * MeasurementDetails for details.
1058  */
1060 
1061  /** The front left wheel speed (in m/s). Set to NAN if not available. */
1062  float front_left_speed_mps = NAN;
1063 
1064  /** The front right wheel speed (in m/s). Set to NAN if not available. */
1065  float front_right_speed_mps = NAN;
1066 
1067  /** The rear left wheel speed (in m/s). Set to NAN if not available. */
1068  float rear_left_speed_mps = NAN;
1069 
1070  /** The rear right wheel speed (in m/s). Set to NAN if not available. */
1071  float rear_right_speed_mps = NAN;
1072 
1073  /**
1074  * The transmission gear currently in use, or direction of motion, if
1075  * available.
1076  *
1077  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
1078  * direction information is available externally.
1079  */
1081 
1082  /**
1083  * `true` if the wheel speeds are signed (positive forward, negative reverse),
1084  * or `false` if the values are unsigned (positive in both directions).
1085  */
1086  bool is_signed = true;
1087 
1088  uint8_t reserved[2] = {0};
1089 };
1090 
1091 /**
1092  * @brief (Deprecated) Vehicle body speed measurement (@ref
1093  * MessageType::DEPRECATED_VEHICLE_SPEED_MEASUREMENT, version 1.0).
1094  * @ingroup measurement_messages
1095  *
1096  * @deprecated
1097  * This message is deprecated as of version 1.18.0 and may be removed in the
1098  * future. It should not used for new development. See @ref VehicleSpeedInput
1099  * and @ref VehicleSpeedOutput instead.
1100  */
1102  static constexpr MessageType MESSAGE_TYPE =
1104  static constexpr uint8_t MESSAGE_VERSION = 0;
1105 
1106  /**
1107  * Measurement timestamp and additional information, if available. See @ref
1108  * MeasurementDetails for details.
1109  */
1111 
1112  /** The current vehicle speed estimate (in m/s). */
1113  float vehicle_speed_mps = NAN;
1114 
1115  /**
1116  * The transmission gear currently in use, or direction of motion, if
1117  * available.
1118  *
1119  * Set to @ref GearType::FORWARD or @ref GearType::REVERSE where vehicle
1120  * direction information is available externally.
1121  */
1123 
1124  /**
1125  * `true` if the wheel speeds are signed (positive forward, negative reverse),
1126  * or `false` if the values are unsigned (positive in both directions).
1127  */
1128  bool is_signed = true;
1129 
1130  uint8_t reserved[2] = {0};
1131 };
1132 
1133 ////////////////////////////////////////////////////////////////////////////////
1134 // Attitude Sensor Definitions
1135 ////////////////////////////////////////////////////////////////////////////////
1136 
1137 /**
1138  * @brief Multi-antenna GNSS attitude sensor measurement output with offset
1139  * corrections applied (@ref MessageType::GNSS_ATTITUDE_OUTPUT, version
1140  * 1.0).
1141  * @ingroup measurement_messages
1142  *
1143  * This message is an output from the device contaning orientation measurements
1144  * generated using multiple GNSS antennas/receivers. On supported devices, the
1145  * device will measure vehicle yaw (heading) and pitch based on the relative
1146  * positions of two GNSS antennas. When more than two antennas are present, the
1147  * device may additionally measure roll angle.
1148  *
1149  * @note
1150  * This message contains vehicle body angle measurements generated from GNSS
1151  * measurements. These measurements inputs to the navigation engine, not the
1152  * filtered output from engine. They may be less accurate than the vehicle body
1153  * orientation estimate in @ref PoseMessage.
1154  *
1155  * The measurements in this message have user-specified corrections applied for
1156  * the horizontal and vertical offsets between the two GNSS antennas. See also
1157  * @ref RawGNSSAttitudeOutput.
1158  */
1160  static constexpr MessageType MESSAGE_TYPE = MessageType::GNSS_ATTITUDE_OUTPUT;
1161  static constexpr uint8_t MESSAGE_VERSION = 0;
1162 
1163  /**
1164  * Measurement timestamp and additional information, if available. See @ref
1165  * MeasurementDetails for details.
1166  */
1168 
1169  /**
1170  * Set to @ref SolutionType::RTKFixed when heading is available, or @ref
1171  * SolutionType::Invalid otherwise.
1172  */
1174 
1175  uint8_t reserved[3] = {0};
1176 
1177  /** A bitmask of flags associated with the solution. */
1178  uint32_t flags = 0;
1179 
1180  /**
1181  * The measured vehicle body orientation (in degrees).
1182  *
1183  * YPR is defined as an intrinsic Euler-321 rotation, i.e., yaw, pitch, then
1184  * roll with respect to the local ENU tangent plane. See @ref
1185  * PoseMessage::ypr_deg for a complete rotation definition.
1186  *
1187  * If any angles are not available, they will be set to `NAN`. For
1188  * dual-antenna systems, the device will measure yaw and pitch, but not roll.
1189  *
1190  * Note that yaw is measured from east in a counter-clockwise direction. For
1191  * example, north is +90 degrees. Heading with respect to true north can be
1192  * computed as `heading = 90.0 - ypr_deg[0]`.
1193  */
1194  float ypr_deg[3] = {NAN, NAN, NAN};
1195 
1196  /**
1197  * The standard deviation of the orientation measurement (in degrees).
1198  */
1199  float ypr_std_deg[3] = {NAN, NAN, NAN};
1200 
1201  /**
1202  * The estimated distance between primary and secondary antennas (in meters).
1203  */
1204  float baseline_distance_m = NAN;
1205 
1206  /**
1207  * The standard deviation of the baseline distance estimate (in meters).
1208  */
1209  float baseline_distance_std_m = NAN;
1210 };
1211 
1212 /**
1213  * @brief Raw (uncorrected) GNSS attitude sensor measurement output (@ref
1214  * MessageType::RAW_GNSS_ATTITUDE_OUTPUT, version 1.0).
1215  * @ingroup measurement_messages
1216  *
1217  * This message is an output from the device contaning raw orientation
1218  * measurements generated using multiple GNSS antennas/receivers that have not
1219  * been corrected for horizontal/vertical offsets between the antennas. Here,
1220  * orientation is represented as the vector from a primary GNSS antenna to a
1221  * secondary GNSS antenna.
1222  *
1223  * For vehicle body angle measurements, and for measurements corrected for
1224  * horizontal/vertical offsets, see @ref GNSSAttitudeOutput.
1225  */
1227  static constexpr MessageType MESSAGE_TYPE =
1229  static constexpr uint8_t MESSAGE_VERSION = 0;
1230 
1231  /**
1232  * Measurement timestamp and additional information, if available. See @ref
1233  * MeasurementDetails for details.
1234  */
1236 
1237  /**
1238  * Set to @ref SolutionType::RTKFixed when heading is available, or @ref
1239  * SolutionType::Invalid otherwise.
1240  */
1242 
1243  uint8_t reserved[3] = {0};
1244 
1245  /** A bitmask of flags associated with the solution. */
1246  uint32_t flags = 0;
1247 
1248  /**
1249  * The position of the secondary GNSS antenna relative to the primary antenna
1250  * (in meters), resolved with respect to the local ENU tangent plane: east,
1251  * north, up.
1252  *
1253  * Position is measured with respect to the primary antenna as follows:
1254  * @f[
1255  * \Delta r_{ENU} = C^{ENU}_{ECEF} (r_{Secondary, ECEF} - r_{Primary, ECEF})
1256  * @f]
1257  */
1258  float relative_position_enu_m[3] = {NAN, NAN, NAN};
1259 
1260  /**
1261  * The standard deviation of the relative position vector (in meters),
1262  * resolved with respect to the local ENU tangent plane: east, north, up.
1263  */
1264  float position_std_enu_m[3] = {NAN, NAN, NAN};
1265 };
1266 
1267 ////////////////////////////////////////////////////////////////////////////////
1268 // Binary Sensor Data Definitions
1269 ////////////////////////////////////////////////////////////////////////////////
1270 
1271 /**
1272  * @brief A block of incoming sensor data whose definition depends on the value
1273  * of @ ref data_type. (@ref MessageType::INPUT_DATA_WRAPPER).
1274  * @ingroup measurement_messages
1275  *
1276  * This message has the remainder of the payload_size_bytes filled with the
1277  * wrapped data. The payload is not guaranteed to be aligned to a specific
1278  * message boundary, or to contain complete messages.
1279  *
1280  * ```
1281  * {MessageHeader, InputDataWrapperMessage, [wrapped data]}
1282  * ```
1283  */
1285  static constexpr MessageType MESSAGE_TYPE = MessageType::INPUT_DATA_WRAPPER;
1286  static constexpr uint8_t MESSAGE_VERSION = 0;
1287 
1288 #if !defined(_MSC_VER)
1289  // Default member initializers for bit-fields only available with c++20.
1290  InputDataWrapperMessage() : system_time_cs(0) {}
1291 #endif
1292 
1293 // The MSVC compiler does not allow unaligned bit fields:
1294 // https://stackoverflow.com/questions/4310728/forcing-unaligned-bitfield-packing-in-msvc
1295 // unlike Clang and GCC. This means that `uint64_t system_time_cs : 40;` is 5
1296 // bytes in GCC and 8 bytes in MSVC. On MSVC, you must cast
1297 // @ref system_time_cs_bytes to read and write the timestamp.
1298 #if defined(_MSC_VER)
1299  /**
1300  * 5 byte system wall-clock timestamp in centiseconds (hundredths of a
1301  * second). Set to POSIX time (time since 1/1/1970) where available.
1302  */
1303  uint8_t system_time_cs_bytes[5] = {0};
1304 #else
1305  /**
1306  * 5 byte system wall-clock timestamp in centiseconds (hundredths of a
1307  * second). Set to POSIX time (time since 1/1/1970) where available.
1308  */
1309  uint64_t system_time_cs : 40;
1310 #endif
1311 
1312  uint8_t reserved[1] = {0};
1313 
1314  /** Type identifier for the serialized message to follow. */
1315  uint16_t data_type = 0;
1316 
1317  /**
1318  * The rest of this message contains the wrapped data. The size of the data is
1319  * found by subtracting the size of the other fields in this message from the
1320  * header `payload_size_bytes` (i.e. `size_t content_size =
1321  * header->payload_size_bytes - sizeof(InputDataWrapperMessage)`). The data is
1322  * interpreted based on the value of `data_type`.
1323  */
1324 };
1325 static_assert(sizeof(InputDataWrapperMessage) == 8,
1326  "InputDataWrapperMessage does not match expected packed size.");
1327 
1328 #pragma pack(pop)
1329 
1330 } // namespace messages
1331 } // namespace fusion_engine
1332 } // namespace point_one
@ RAW_VEHICLE_SPEED_OUTPUT
RawVehicleSpeedOutput
@ GPS_TIME
Message timestamped in GPS time, referenced to 1980/1/6.
@ CAN
Sensor data captured from a vehicle CAN bus.
SystemTimeSource
The source of a point_one::fusion_engine::messages::Timestamp used to represent the time of applicabi...
Definition: measurements.h:96
@ IMU_INPUT
IMUInput
Raw (uncorrected) dfferential wheel encoder tick output (MessageType::RAW_WHEEL_TICK_OUTPUT,...
Definition: measurements.h:887
(Deprecated) Differential wheel speed measurement (MessageType::DEPRECATED_WHEEL_SPEED_MEASUREMENT,...
Differential wheel encoder tick input (MessageType::WHEEL_TICK_INPUT, version 1.0).
Definition: measurements.h:824
MessageType
Identifiers for the defined output message types.
Definition: defs.h:34
Library portability helper definitions.
MeasurementDetails details
Measurement timestamp and additional information, if available.
Definition: measurements.h:250
Raw (uncorrected) single wheel encoder tick output (MessageType::RAW_VEHICLE_TICK_OUTPUT,...
@ INVALID
Timestamp not valid.
Single wheel encoder tick input, representing vehicle body speed (MessageType::VEHICLE_TICK_INPUT,...
Definition: measurements.h:962
SolutionType
Navigation solution type definitions.
Definition: defs.h:503
P1_CONSTEXPR_FUNC const char * to_string(ConfigType type)
Get a human-friendly string name for the specified ConfigType.
Timestamp measurement_time
The measurement time of applicability, if available, in a user-specified time base.
Definition: measurements.h:198
#define P1_ALIGNAS(N)
Definition: portability.h:57
@ RAW_VEHICLE_TICK_OUTPUT
RawVehicleTickOutput
@ DEPRECATED_WHEEL_SPEED_MEASUREMENT
DeprecatedWheelSpeedMeasurement
MeasurementDetails details
Measurement timestamp and additional information, if available.
Definition: measurements.h:896
Raw (uncorrected) vehicle body speed measurement output (MessageType::RAW_VEHICLE_SPEED_OUTPUT,...
Definition: measurements.h:760
@ SERIAL
Sensor data provided over a serial connection.
@ INPUT_DATA_WRAPPER
InputDataWrapperMessage
MeasurementDetails details
Measurement timestamp and additional information, if available.
Definition: measurements.h:335
@ RAW_WHEEL_SPEED_OUTPUT
RawWheelSpeedOutput
@ TIMESTAMPED_ON_RECEPTION
Message timestamped in system time, generated when received by the device.
MeasurementDetails details
Measurement timestamp and additional information, if available.
Definition: measurements.h:583
@ NEUTRAL
The vehicle is in neutral.
MeasurementDetails details
Measurement timestamp and additional information, if available.
Raw (uncorrected) dfferential wheel speed measurement output (MessageType::RAW_WHEEL_SPEED_OUTPUT,...
Definition: measurements.h:567
MeasurementDetails details
Measurement timestamp and additional information, if available.
Timestamp p1_time
The P1 time corresponding with the measurement time of applicability, if available.
Definition: measurements.h:225
@ DEPRECATED_VEHICLE_SPEED_MEASUREMENT
DeprecatedVehicleSpeedMeasurement
The base class for all message payloads.
Definition: defs.h:685
Raw (uncorrected) IMU sensor measurement output (MessageType::RAW_IMU_OUTPUT, version 1....
Definition: measurements.h:327
SensorDataSource
The source of received sensor measurements, if known.
Definition: measurements.h:33
A block of incoming sensor data whose definition depends on the value of @ ref data_type.
@ SENDER_SYSTEM_TIME
Message timestamp was generated from a monotonic clock of an external system.
MeasurementDetails details
Measurement timestamp and additional information, if available.
@ REVERSE
The vehicle is in reverse.
Differential wheel speed measurement input (MessageType::WHEEL_SPEED_INPUT, version 1....
Definition: measurements.h:434
@ Invalid
Invalid, no position available.
GNSS signal and frequency type definitions.
Definition: logging.h:38
@ GNSS_ATTITUDE_OUTPUT
GNSSAttitudeOutput
MeasurementDetails details
Measurement timestamp and additional information, if available.
Definition: measurements.h:776
MeasurementDetails details
Measurement timestamp and additional information, if available.
Definition: measurements.h:666
@ RAW_GNSS_ATTITUDE_OUTPUT
RawGNSSAttitudeOutput
uint64_t system_time_cs
5 byte system wall-clock timestamp in centiseconds (hundredths of a second).
@ IMU_OUTPUT
IMUOutput
Timestamp p1_time
The time of the measurement, in P1 time (beginning at power-on).
Definition: measurements.h:289
@ RAW_IMU_OUTPUT
RawIMUOutput
GearType
The current transmission gear used by the vehicle.
Definition: measurements.h:365
Raw (uncorrected) GNSS attitude sensor measurement output (MessageType::RAW_GNSS_ATTITUDE_OUTPUT,...
std::ostream p1_ostream
Definition: portability.h:75
IMU sensor measurement output with calibration and corrections applied (MessageType::IMU_OUTPUT,...
Definition: measurements.h:284
@ VEHICLE_SPEED_INPUT
VehicleSpeedInput
MeasurementDetails details
Measurement timestamp and additional information, if available.
Definition: measurements.h:449
p1_ostream & operator<<(p1_ostream &stream, ConfigType type)
ConfigType stream operator.
MeasurementDetails details
Measurement timestamp and additional information, if available.
The time of applicability and additional information for an incoming sensor measurement.
Definition: measurements.h:191
@ NETWORK
Sensor data provided over a network connection.
@ WHEEL_SPEED_INPUT
WheelSpeedInput
@ UNKNOWN
Data source not known.
@ WHEEL_SPEED_OUTPUT
WheelSpeedOutput
@ RAW_WHEEL_TICK_OUTPUT
RawWheelTickOutput
#define P1_CONSTEXPR_FUNC
Definition: portability.h:105
@ INTERNAL
Sensor data captured internal to the device (embedded IMU, GNSS receiver, etc.).
@ VEHICLE_SPEED_OUTPUT
VehicleSpeedOutput
@ VEHICLE_TICK_INPUT
VehicleTickInput
Timestamp p1_time
The time of the measurement, in P1 time (beginning at power-on).
Definition: measurements.h:723
MeasurementDetails details
Measurement timestamp and additional information, if available.
Timestamp p1_time
The time of the measurement, in P1 time (beginning at power-on).
Definition: measurements.h:525
(Deprecated) Vehicle body speed measurement (MessageType::DEPRECATED_VEHICLE_SPEED_MEASUREMENT,...
@ P1_TIME
Message timestamped in P1 time.
Vehicle body speed measurement input (MessageType::VEHICLE_SPEED_INPUT, version 1....
Definition: measurements.h:651
@ FORWARD
The vehicle is in a forward gear.
Point One FusionEngine output message common definitions.
@ PARK
The vehicle is parked.
Generic timestamp representation.
Definition: defs.h:586
InputDataWrapperMessage()
Vehicle body speed measurement output with calibration and corrections applied (MessageType::VEHICLE_...
Definition: measurements.h:711
MeasurementDetails details
Measurement timestamp and additional information, if available.
Definition: measurements.h:970
@ HARDWARE_IO
Sensor data generated via hardware voltage signal (wheel tick, external event, etc....
@ UNKNOWN
The transmission gear is not known, or does not map to a supported GearType.
Differential wheel speed measurement output with calibration and corrections applied (MessageType::WH...
Definition: measurements.h:513
Multi-antenna GNSS attitude sensor measurement output with offset corrections applied (MessageType::G...
MeasurementDetails details
Measurement timestamp and additional information, if available.
Definition: measurements.h:832
@ WHEEL_TICK_INPUT
WheelTickInput
IMU sensor measurement input (MessageType::IMU_INPUT, version 1.0).
Definition: measurements.h:242