IMUOutput Struct
IMU sensor measurement output with calibration and corrections applied (MessageType::IMU_OUTPUT, version 1.0). More...
Declaration
Included Headers
Base struct
| struct | MessagePayload |
|
The base class for all message payloads. More... | |
Public Member Attributes Index
| double | accel_mps2[3] = {NAN, NAN, NAN} |
|
Corrected vehicle x/y/z acceleration (in meters/second^2), resolved in the body frame. More... | |
| double | accel_std_mps2[3] = {NAN, NAN, NAN} |
|
Corrected vehicle x/y/z acceleration standard deviation (in meters/second^2), resolved in the body frame. More... | |
| double | gyro_rps[3] = {NAN, NAN, NAN} |
|
Corrected vehicle x/y/z rate of rotation (in radians/second), resolved in the body frame. More... | |
| double | gyro_std_rps[3] = {NAN, NAN, NAN} |
|
Corrected vehicle x/y/z rate of rotation standard deviation (in radians/second), resolved in the body frame. More... | |
| Timestamp | p1_time |
|
The time of the measurement, in P1 time (beginning at power-on). More... | |
Public Static Attributes Index
| static constexpr MessageType | MESSAGE_TYPE = MessageType::IMU_OUTPUT |
| static constexpr uint8_t | MESSAGE_VERSION = 0 |
Description
IMU sensor measurement output with calibration and corrections applied (MessageType::IMU_OUTPUT, version 1.0).
This message is an output from the device containing IMU acceleration and rotation rate measurements. The measurements been corrected for biases and scale factors, and have been rotated into the vehicle body frame from the original IMU orientation, including calibrated mounting error estimates.
See also RawIMUOutput.
Definition at line 284 of file measurements.h.
Public Member Attributes
accel_mps2
Corrected vehicle x/y/z acceleration (in meters/second^2), resolved in the body frame.
Definition at line 295 of file measurements.h.
accel_std_mps2
Corrected vehicle x/y/z acceleration standard deviation (in meters/second^2), resolved in the body frame.
Definition at line 301 of file measurements.h.
gyro_rps
Corrected vehicle x/y/z rate of rotation (in radians/second), resolved in the body frame.
Definition at line 307 of file measurements.h.
gyro_std_rps
Corrected vehicle x/y/z rate of rotation standard deviation (in radians/second), resolved in the body frame.
Definition at line 313 of file measurements.h.
p1_time
|
The time of the measurement, in P1 time (beginning at power-on).
Definition at line 289 of file measurements.h.
Public Static Attributes
MESSAGE_TYPE
| constexpr static |
Definition at line 285 of file measurements.h.
MESSAGE_VERSION
| constexpr static |
Definition at line 286 of file measurements.h.
The documentation for this struct was generated from the following file:
Generated via doxygen2docusaurus 2.0.0 by Doxygen 1.9.8.