point_one::fusion_engine::messages::CalibrationStatusMessage Struct Reference

Detailed Description

Device calibration status update.

(MessageType::CALIBRATION_STATUS, version 1.1).

Definition at line 405 of file solution.h.

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

#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
 

Member Data Documentation

◆ accel_bias_percent_complete

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 461 of file solution.h.

◆ calibration_stage

CalibrationStage point_one::fusion_engine::messages::CalibrationStatusMessage::calibration_stage = CalibrationStage::UNKNOWN

The current calibration stage.

Definition at line 418 of file solution.h.

◆ gyro_bias_percent_complete

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 455 of file solution.h.

◆ MESSAGE_TYPE

constexpr MessageType point_one::fusion_engine::messages::CalibrationStatusMessage::MESSAGE_TYPE = MessageType::CALIBRATION_STATUS
staticconstexpr

Definition at line 406 of file solution.h.

◆ MESSAGE_VERSION

constexpr uint8_t point_one::fusion_engine::messages::CalibrationStatusMessage::MESSAGE_VERSION = 1
staticconstexpr

Definition at line 407 of file solution.h.

◆ min_travel_distance_m

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 482 of file solution.h.

◆ mounting_angle_max_std_dev_deg

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 488 of file solution.h.

◆ mounting_angle_percent_complete

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 467 of file solution.h.

◆ p1_time

Timestamp point_one::fusion_engine::messages::CalibrationStatusMessage::p1_time

The most recent P1 time, if available.

Definition at line 410 of file solution.h.

◆ state_verified

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 447 of file solution.h.

◆ travel_distance_m

float point_one::fusion_engine::messages::CalibrationStatusMessage::travel_distance_m = 0.0

The accumulated calibration travel distance (in meters).

Definition at line 432 of file solution.h.

◆ ypr_deg

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 423 of file solution.h.

◆ ypr_std_dev_deg

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 429 of file solution.h.


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