Skip to main content

CalibrationStatusMessage Struct

Device calibration status update. More...

Declaration

struct point_one::fusion_engine::messages::CalibrationStatusMessage { ... }

Included Headers

Base struct

structMessagePayload

The base class for all message payloads. More...

Public Member Attributes Index

Timestampp1_time

The most recent P1 time, if available. More...

Public Static Attributes Index

static constexpr MessageTypeMESSAGE_TYPE = MessageType::CALIBRATION_STATUS
static constexpr uint8_tMESSAGE_VERSION = 1

Calibration State Data Index

CalibrationStagecalibration_stage = CalibrationStage::UNKNOWN

The current calibration stage. More...

floatypr_deg[3] = {NAN, NAN, NAN}

The IMU yaw, pitch, and roll mounting angle offsets (in degrees). More...

floatypr_std_dev_deg[3] = {NAN, NAN, NAN}

The IMU yaw, pitch, and roll mounting angle standard deviations (in degrees). More...

floattravel_distance_m = 0.0

The accumulated calibration travel distance (in meters). More...

Calibration Process Status Index

uint8_tstate_verified {0}

Set to 1 once the navigation engine state is validated after initialization. More...

uint8_tgyro_bias_percent_complete = 0

The completion percentage for gyro bias estimation, stored with a scale factor of 0.5% (0-200). More...

uint8_taccel_bias_percent_complete = 0

The completion percentage for accelerometer bias estimation, stored with a scale factor of 0.5% (0-200). More...

uint8_tmounting_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

floatmin_travel_distance_m = NAN

The minimum accumulated calibration travel distance needed to complete mounting angle calibration. More...

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

Public Member Attributes

p1_time

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

The most recent P1 time, if available.

Definition at line 421 of file solution.h.

Public Static Attributes

MESSAGE_TYPE

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

Definition at line 417 of file solution.h.

417 static constexpr MessageType MESSAGE_TYPE = MessageType::CALIBRATION_STATUS;

MESSAGE_VERSION

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

Definition at line 418 of file solution.h.

418 static constexpr uint8_t MESSAGE_VERSION = 1;

Calibration State Data

calibration_stage

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

The current calibration stage.

Definition at line 429 of file solution.h.

429 CalibrationStage calibration_stage = CalibrationStage::UNKNOWN;

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

443 float travel_distance_m = 0.0;

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

434 float ypr_deg[3] = {NAN, NAN, NAN};

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

440 float ypr_std_dev_deg[3] = {NAN, NAN, NAN};

Calibration Process Status

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

472 uint8_t accel_bias_percent_complete = 0;

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

466 uint8_t gyro_bias_percent_complete = 0;

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

478 uint8_t mounting_angle_percent_complete = 0;

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

458 uint8_t state_verified{0};

Calibration Thresholds

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

493 float min_travel_distance_m = NAN;

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

499 float mounting_angle_max_std_dev_deg[3] = {NAN, NAN, NAN};

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


Generated via doxygen2docusaurus 2.0.0 by Doxygen 1.9.8.