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