CalibrationStatusMessage Struct
Device calibration status update. More...
Declaration
Included Headers
Base struct
| struct | MessagePayload |
|
The base class for all message payloads. More... | |
Public Member Attributes Index
| Timestamp | p1_time |
|
The most recent P1 time, if available. More... | |
Public Static Attributes Index
| static constexpr MessageType | MESSAGE_TYPE = MessageType::CALIBRATION_STATUS |
| static constexpr uint8_t | MESSAGE_VERSION = 1 |
Calibration State Data Index
| 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 Index
| 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 Index
| 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... | |
Description
Device calibration status update.
(MessageType::CALIBRATION_STATUS, version 1.1).
Definition at line 576 of file solution.h.
Public Member Attributes
p1_time
|
The most recent P1 time, if available.
Definition at line 581 of file solution.h.
Public Static Attributes
MESSAGE_TYPE
| constexpr static |
Definition at line 577 of file solution.h.
MESSAGE_VERSION
| constexpr static |
Definition at line 578 of file solution.h.
Calibration State Data
calibration_stage
|
The current calibration stage.
Definition at line 589 of file solution.h.
travel_distance_m
|
The accumulated calibration travel distance (in meters).
Definition at line 603 of file solution.h.
ypr_deg
The IMU yaw, pitch, and roll mounting angle offsets (in degrees).
Definition at line 594 of file solution.h.
ypr_std_dev_deg
Calibration Process Status
accel_bias_percent_complete
|
The completion percentage for accelerometer bias estimation, stored with a scale factor of 0.5% (0-200).
Definition at line 632 of file solution.h.
gyro_bias_percent_complete
|
The completion percentage for gyro bias estimation, stored with a scale factor of 0.5% (0-200).
Definition at line 626 of file solution.h.
mounting_angle_percent_complete
|
The completion percentage for IMU mounting angle estimation, stored with a scale factor of 0.5% (0-200).
Definition at line 638 of file solution.h.
state_verified
|
Set to 1 once the navigation engine state is validated after initialization.
Definition at line 618 of file solution.h.
Calibration Thresholds
min_travel_distance_m
|
The minimum accumulated calibration travel distance needed to complete mounting angle calibration.
Definition at line 653 of file solution.h.
mounting_angle_max_std_dev_deg
|
The max threshold for each of the YPR mounting angle states (in degrees), above which calibration is incomplete.
Definition at line 659 of file solution.h.
The documentation for this struct was generated from the following file:
Generated via doxygen2docusaurus 2.0.0 by Doxygen 1.9.8.