System Status¶
Solution Status¶
Solution Alignment¶
Solution alignment occurs when aiding sensor and state estimation are in agreement and indicates that solution output can be trusted.
Heading Alignment¶
Heading alignment varies based on available sensors and conditions of motion.
Stationary INS and AHRS (no GPS) use the magnetometer for heading alignment. The INS solution will start and remain in INS_ALIGNING status (1) until the magnetometer calibration is validated. The magnetometer requires +- 45 degrees of rotation to validate calibration and ensure accurate heading.
Moving INS (under accelerated conditions) or Dual GNSS (two GPS antennas using RTK compassing) can align the heading without use of the magnetometer. The INS solution will start in INS_ALIGNING status (1) and immediately proceed to INS_NAV_IS_GOOD status (3) with GPS lock for Dual GNSS and accelerated horizontal movement for single GNSS INS use.
LED Status¶
System status including GPS lock, INS alignment, and time synchronization are reported via the top tri-color LED. This LED can be disabled (turned off) by setting bit 0x4 of DID_FLASH_CONFIG.sysCfgBits.
LED Behavior | Solution Status # |
Status | Description |
---|---|---|---|
White ![]() |
1 | Solution Aligning | The solution is aligning on startup |
Cyan ![]() |
2 | Solution Alignment Complete | The solution has aligned but insufficient dynamics have been completed for the variance to reach nominal conditions. |
Green ![]() |
3 | Solution Good – NAV | The solution is in Navigation mode and state estimate is good. |
Blue ![]() |
5 | Solution Good – AHRS | The solution is in AHRS mode and state estimate is good. There is no valid position or velocity data from GPS or other aiding sensor. Only the attitude states are estimated |
Orange ![]() |
4,6 | Solution High Variance | The solution is in Navigation or AHRS mode but variance (uncertainty) is high. This may be caused by excessive sensor noise such as vibration, magnetic interference, or poor GPS visibility or multipath errors. See DID_INL2_VARIANCE. |
Purple ![]() |
Magnetometer Recalibration | The system is collecting new magnetometer calibration data and requires rotation. | |
Cyan Fading ![]() |
Bootloader Waiting | The bootloader has started and is waiting for communications. | |
Purple Fast Blink ![]() |
Firmware Upload | The bootloader is uploading the embedded firmware. | |
Orange Fast Blink ![]() |
Firmware Verification | The bootloader is verifying the embedded firmware. | |
Red ![]() |
Bootloader Failure | The bootloader has experienced a failure on startup. | |
Can combine with behaviors above | |||
Red pulse every 1s ![]() |
GPS PPS Sync | The system has received and synchronized local time to UTC time using the GPS PPS signal. | |
Red/purple pulse every 1s ![]() |
RTK Base Data Received | The system is receiving RTK base station data. | |
Purple pulse every 1s ![]() |
RTK Fix Status | The GPS has valid RTK fix and high precision positioning |
Status flags described in this section that can be observed by bitwise ANDing any of the status flag bitmasks with the corresponding status flags variable.
Status Flags¶
This section lists the commonly used status flags. A complete listing of status flags is available in data_sets.h.
insStatus – INS Status Flags¶
The INS status flags, insStatus, are found in the DID_INS1, DID_INS2, DID_INS3, and DID_SYS_PARAMS messages. Bitmasks for the insStatus flags are defined in eInsStatusFlags in data_sets.h.
Field | Description |
---|---|
INS_STATUS_ALIGN_COARSE_MASK | Position, Velocity & Attitude are usable. Variance of the state estimate are outside spec. |
INS_STATUS_ALIGN_GOOD_MASK | Position, Velocity & Attitude are good. Variance of state estimate are within spec. |
INS_STATUS_GPS_AIDING_HEADING | INS heading are being corrected by GPS. |
INS_STATUS_GPS_AIDING_POS | INS position and velocity are being corrected by GPS. |
INS_STATUS_GPS_UPDATE_IN_SOLUTION | GPS update event occurred in INS, potentially causing discontinuity in position path. |
INS_STATUS_MAG_AIDING_HEADING | INS heading are being corrected by magnetometer. |
INS_STATUS_NAV_MODE | AHRS = 0 (no position or velocity), NAV = 1 |
INS_STATUS_MAG_RECALIBRATING | Magnetometer is recalibrating. |
INS_STATUS_MAG_NOT_GOOD | Magnetometer is experiencing interference. |
INS_STATUS_SOLUTION_MASK | 0=INS_INACTIVE – The INS is not runnning 1=INS_STATUS_SOLUTION_ALIGNING – The INS is aligning on startup 2=INS_STATUS_SOLUTION_ALIGNMENT_COMPLETE – The INS has aligned but insufficient dynamics have been completed for the variance to reach nominal conditions. 3=INS_STATUS_SOLUTION_NAV – The INS is in NAV mode and the state estimate is good. 4=INS_STATUS_SOLUTION_NAV_HIGH_VARIANCE – The INS is in NAV mode and the state estimate is experiencing high variance. This may be caused by excessive noise on one or more sensors, such as vibration, magnetic interference, poor GPS sky visibility and/or GPS multipath errors. See DID_INL2_VARIANCE. 5=INS_STATUS_SOLUTION_AHRS – INS is in AHRS mode and the solution is good. There is no valid position correction data from GPS or other aiding sensor. Only the attitude states are estimated. 6=INS_STATUS_SOLUTION_AHRS_HIGH_VARIANCE – INS is in AHRS mode and the state estimate has high variance. See DID_INL2_VARIANCE. |
hdwStatus – Hardware Status Flags¶
The hardware status flags, hdwStatus, are found in the DID_INS1
, DID_INS2
, DID_INS3
, and DID_SYS_PARAMS
messages. Bitmasks for the hdwStatus flags are defined in eHdwStatusFlags
in data_sets.h.
Field | Description |
---|---|
HDW_STATUS_MOTION_MASK | Accelerometers and Gyros are operational |
HDW_STATUS_GPS_SATELLITE_RX | Antenna is connected to the GPS receiver and signal is received |
HDW_STATUS_STROBE_IN_EVENT | Event occurred on strobe input pin |
HDW_STATUS_SATURATION_MASK | Acc., Gyro, Mag or Baro is saturated |
HDW_STATUS_SELF_TEST_FAULT | BIT has failed |
HDW_STATUS_ERR_TEMPERATURE | Outside of operational range |
HDW_STATUS_FAULT_BOD_RESET | Low Power Reset |
HDW_STATUS_FAULT_POR_RESET | Software or Triggered Reset |
Built-in Test (BIT)¶
Built-in test (BIT) is enabled by setting DID_BIT.state
to any of the following values.
BIT_STATE_CMD_FULL_STATIONARY = (int)2, // (FULL) Comprehensive test. Requires system be completely stationary without vibrations.
BIT_STATE_CMD_BASIC_MOVING = (int)3, // (BASIC) Ignores sensor output. Can be run while moving. This mode is automatically run after bootup.
BIT_STATE_CMD_FULL_STATIONARY_HIGH_ACCURACY = (int)4, // Same as BIT_STATE_CMD_FULL_STATIONARY but with higher requirements for accuracy.
BIT takes about 5 seconds to run, and is completed when DID_BIT.state == BIT_STATE_DONE (1)
. All BIT tests except those related to GPS require the system to be stationary to be accurate.
hdwBitStatus – Hardware BIT Flags¶
Hardware BIT flags are contained in hdwBitStatus, found in the DID_BIT
message. Bitmasks for the hdwBitStatus
flags are defined in eHdwBitStatusFlags
in data_sets.h.
Field | Description |
---|---|
HDW_BIT_PASSED_ALL | All HBIT are passed |
HDW_BIT_PASSED_AHRS | All Self Tests passed without GPS signal |
HDW_BIT_FAILED_MASK | One of the built-in tests failed |
HDW_BIT_FAULT_GPS_NO_COM | No GPS Signal |
HDW_BIT_FAULT_GPS_POOR_CNO | Poor GPS signal. Check Antenna |
HDW_BIT_FAULT_GPS_ACCURACY | Poor GPS Accuracy or Low number of satellites |
calBitStatus – Calibration BIT Flags¶
Calibration BIT flags are contained in calBitStatus, found in the DID_BIT
message. Bitmasks for the calBitStatus
flags are defined in eCalBitStatusFlags
in data_sets.h.
Field | Description |
---|---|
CAL_BIT_PASSED_ALL | Passed all calibration checks |
CAL_BIT_FAILED_MASK | One of the calibration checks failed |
Health Monitoring¶
This section illustrates tests used for system health monitoring in common application.
-
Communication Check
To check that cabling between the unit and the application is working after initialization, expect that the initial expected packets are received within 3 seconds.
-
Sensor Test (Must be Stationary)
These tests are ideal for manufacturing and periodic in-field testing. Initiate by setting
DID_BIT.state = 2
.
Test | Description |
---|---|
hdwBitStatus & HDW_BIT_PASSED_ALL | Hardware is good |
calBitStatus & CAL_BIT_PASSED_ALL | Sensor calibration is good |
-
GPS Hardware Test
Initiate by setting
DID_BIT.state = 2
.
Test | Description |
---|---|
hdwBitStatus & HDW_BIT_FAULT_GPS_NO_COM | No GPS serial communications. |
hdwBitStatus & HDW_BIT_FAULT_GPS_POOR_CNO | Poor GPS signal strength. Check antenna. |
- GPS Lock Test
Test | Description |
---|---|
hdwStatus & INS_STATUS_USING_GPS_IN_SOLUTION | GPS is being fused into INS solution |
- INS Output Valid
Test | Description |
---|---|
insStatus & INS_STATUS_ATT_ALIGN_GOOD | Attitude estimates are valid |
insStatus & INS_STATUS_VEL_ALIGN_GOOD | Velocity estimates are valid |
insStatus & INS_STATUS_POS_ALIGN_GOOD | Position estimates are valid |
-
System Temperature
System temperature is available at DID_SYS_SENSORS.temp.
-
Communications Errors
HDW_STATUS_COM_PARSE_ERROR_COUNT(DID_SYS_SENSORS.hStatus) is the number of parsed packet errors encountered.