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 IMU sensor measurement data (@ref MessageType::IMU_MEASUREMENT,
30  * version 1.0).
31  * @ingroup measurement_messages
32  *
33  * @note
34  * The data contained in this message has been corrected for accelerometer and
35  * gyro biases and scale factors, and has been rotated into the vehicle body
36  * frame from the original IMU orientation.
37  */
38 struct alignas(4) IMUMeasurement : public MessagePayload {
40  static constexpr uint8_t MESSAGE_VERSION = 0;
41 
42  /** The time of the message, in P1 time (beginning at power-on). */
44 
45  /**
46  * Corrected vehicle x/y/z acceleration (in meters/second^2), resolved in the
47  * body frame.
48  */
49  double accel_mps2[3] = {NAN, NAN, NAN};
50 
51  /**
52  * Corrected vehicle x/y/z acceleration standard deviation (in
53  * meters/second^2), resolved in the body frame.
54  */
55  double accel_std_mps2[3] = {NAN, NAN, NAN};
56 
57  /**
58  * Corrected vehicle x/y/z rate of rotation (in radians/second), resolved in
59  * the body frame.
60  */
61  double gyro_rps[3] = {NAN, NAN, NAN};
62 
63  /**
64  * Corrected vehicle x/y/z rate of rotation standard deviation (in
65  * radians/second), resolved in the body frame.
66  */
67  double gyro_std_rps[3] = {NAN, NAN, NAN};
68 };
69 
70 #pragma pack(pop)
71 
72 } // namespace messages
73 } // namespace fusion_engine
74 } // namespace point_one
static constexpr MessageType MESSAGE_TYPE
Definition: measurements.h:39
MessageType
Identifiers for the defined output message types.
Definition: defs.h:80
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:55
The base class for all message payloads.
Definition: defs.h:192
IMU sensor measurement data (MessageType::IMU_MEASUREMENT, version 1.0).
Definition: measurements.h:38
@ IMU_MEASUREMENT
IMUMeasurement
double gyro_rps[3]
Corrected vehicle x/y/z rate of rotation (in radians/second), resolved in the body frame.
Definition: measurements.h:61
Definition: configuration.h:21
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
Definition: measurements.h:43
static constexpr uint8_t MESSAGE_VERSION
Definition: measurements.h:40
Point One FusionEngine output message common definitions.
Generic timestamp representation.
Definition: defs.h:121
double accel_mps2[3]
Corrected vehicle x/y/z acceleration (in meters/second^2), resolved in the body frame.
Definition: measurements.h:49
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:67