point_one::fusion_engine::messages::IMUOutput Struct Reference

Detailed 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 286 of file measurements.h.

Inheritance diagram for point_one::fusion_engine::messages::IMUOutput:
point_one::fusion_engine::messages::MessagePayload

#include <point_one/fusion_engine/messages/measurements.h>

Public Attributes

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...
 

Static Public Attributes

static constexpr MessageType MESSAGE_TYPE = MessageType::IMU_OUTPUT
 
static constexpr uint8_t MESSAGE_VERSION = 0
 

Member Data Documentation

◆ accel_mps2

double point_one::fusion_engine::messages::IMUOutput::accel_mps2[3] = {NAN, NAN, NAN}

Corrected vehicle x/y/z acceleration (in meters/second^2), resolved in the body frame.

Definition at line 297 of file measurements.h.

◆ accel_std_mps2

double point_one::fusion_engine::messages::IMUOutput::accel_std_mps2[3] = {NAN, NAN, NAN}

Corrected vehicle x/y/z acceleration standard deviation (in meters/second^2), resolved in the body frame.

Definition at line 303 of file measurements.h.

◆ gyro_rps

double point_one::fusion_engine::messages::IMUOutput::gyro_rps[3] = {NAN, NAN, NAN}

Corrected vehicle x/y/z rate of rotation (in radians/second), resolved in the body frame.

Definition at line 309 of file measurements.h.

◆ gyro_std_rps

double point_one::fusion_engine::messages::IMUOutput::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.

Definition at line 315 of file measurements.h.

◆ MESSAGE_TYPE

constexpr MessageType point_one::fusion_engine::messages::IMUOutput::MESSAGE_TYPE = MessageType::IMU_OUTPUT
staticconstexpr

Definition at line 287 of file measurements.h.

◆ MESSAGE_VERSION

constexpr uint8_t point_one::fusion_engine::messages::IMUOutput::MESSAGE_VERSION = 0
staticconstexpr

Definition at line 288 of file measurements.h.

◆ p1_time

Timestamp point_one::fusion_engine::messages::IMUOutput::p1_time

The time of the measurement, in P1 time (beginning at power-on).

Definition at line 291 of file measurements.h.


The documentation for this struct was generated from the following file: