Device calibration status update. More...
#include <point_one/fusion_engine/messages/solution.h>
Public Attributes | |
Timestamp | p1_time |
The most recent P1 time, if available. More... | |
Calibration State Data | |
CalibrationStage | calibration_stage = CalibrationStage::UNKNOWN |
The current calibration stage. More... | |
float | ypr_deg [3] = {NAN, NAN, NAN} |
The IMU yaw, pitch, and roll mounting angle offsets (in degrees). More... | |
float | ypr_std_dev_deg [3] = {NAN, NAN, NAN} |
The IMU yaw, pitch, and roll mounting angle standard deviations (in degrees). More... | |
float | travel_distance_m = 0.0 |
The accumulated calibration travel distance (in meters). More... | |
Calibration Process Status | |
uint8_t | state_verified {0} |
Set to 1 once the navigation engine state is validated after initialization. More... | |
uint8_t | gyro_bias_percent_complete = 0 |
The completion percentage for gyro bias estimation, stored with a scale factor of 0.5% (0-200). More... | |
uint8_t | accel_bias_percent_complete = 0 |
The completion percentage for accelerometer bias estimation, stored with a scale factor of 0.5% (0-200). More... | |
uint8_t | mounting_angle_percent_complete = 0 |
The completion percentage for IMU mounting angle estimation, stored with a scale factor of 0.5% (0-200). More... | |
Calibration Thresholds | |
float | min_travel_distance_m = NAN |
The minimum accumulated calibration travel distance needed to complete mounting angle calibration. More... | |
float | mounting_angle_max_std_dev_deg [3] = {NAN, NAN, NAN} |
The max threshold for each of the YPR mounting angle states (in degrees), above which calibration is incomplete. More... | |
Static Public Attributes | |
static constexpr MessageType | MESSAGE_TYPE = MessageType::CALIBRATION_STATUS |
static constexpr uint8_t | MESSAGE_VERSION = 1 |
Device calibration status update.
(MessageType::CALIBRATION_STATUS, version 1).
Definition at line 365 of file solution.h.
uint8_t point_one::fusion_engine::messages::CalibrationStatusMessage::accel_bias_percent_complete = 0 |
The completion percentage for accelerometer bias estimation, stored with a scale factor of 0.5% (0-200).
Definition at line 421 of file solution.h.
CalibrationStage point_one::fusion_engine::messages::CalibrationStatusMessage::calibration_stage = CalibrationStage::UNKNOWN |
The current calibration stage.
Definition at line 378 of file solution.h.
uint8_t point_one::fusion_engine::messages::CalibrationStatusMessage::gyro_bias_percent_complete = 0 |
The completion percentage for gyro bias estimation, stored with a scale factor of 0.5% (0-200).
Definition at line 415 of file solution.h.
|
staticconstexpr |
Definition at line 366 of file solution.h.
|
staticconstexpr |
Definition at line 367 of file solution.h.
float point_one::fusion_engine::messages::CalibrationStatusMessage::min_travel_distance_m = NAN |
The minimum accumulated calibration travel distance needed to complete mounting angle calibration.
Definition at line 442 of file solution.h.
float point_one::fusion_engine::messages::CalibrationStatusMessage::mounting_angle_max_std_dev_deg[3] = {NAN, NAN, NAN} |
The max threshold for each of the YPR mounting angle states (in degrees), above which calibration is incomplete.
Definition at line 448 of file solution.h.
uint8_t point_one::fusion_engine::messages::CalibrationStatusMessage::mounting_angle_percent_complete = 0 |
The completion percentage for IMU mounting angle estimation, stored with a scale factor of 0.5% (0-200).
Definition at line 427 of file solution.h.
Timestamp point_one::fusion_engine::messages::CalibrationStatusMessage::p1_time |
The most recent P1 time, if available.
Definition at line 370 of file solution.h.
uint8_t point_one::fusion_engine::messages::CalibrationStatusMessage::state_verified {0} |
Set to 1 once the navigation engine state is validated after initialization.
Definition at line 407 of file solution.h.
float point_one::fusion_engine::messages::CalibrationStatusMessage::travel_distance_m = 0.0 |
The accumulated calibration travel distance (in meters).
Definition at line 392 of file solution.h.
float point_one::fusion_engine::messages::CalibrationStatusMessage::ypr_deg[3] = {NAN, NAN, NAN} |
The IMU yaw, pitch, and roll mounting angle offsets (in degrees).
Definition at line 383 of file solution.h.
float point_one::fusion_engine::messages::CalibrationStatusMessage::ypr_std_dev_deg[3] = {NAN, NAN, NAN} |
The IMU yaw, pitch, and roll mounting angle standard deviations (in degrees).
Definition at line 389 of file solution.h.