AP_NavEKF2: add initalized flag and change to uint32_t

This commit is contained in:
Peter Hall 2020-02-07 20:33:40 +00:00 committed by Andrew Tridgell
parent 9ec5355dfc
commit e0eeb4f863
3 changed files with 5 additions and 1 deletions

View File

@ -521,5 +521,6 @@ void NavEKF2_core::updateFilterStatus(void)
filterStatus.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE);
filterStatus.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && !extNavUsedForPos; // GPS glitching is affecting navigation accuracy
filterStatus.flags.gps_quality_good = gpsGoodToAlign;
filterStatus.flags.initalized = filterStatus.flags.initalized || healthy();
}

View File

@ -143,7 +143,7 @@ void NavEKF2::Log_Write_NKF4(uint8_t _core, uint64_t time_us) const
offsetEast : (int8_t)(offset.y),
faults : (uint16_t)(faultStatus),
timeouts : (uint8_t)(timeoutStatus),
solution : (uint16_t)(solutionStatus.value),
solution : (uint32_t)(solutionStatus.value),
gps : (uint16_t)(gpsStatus.value),
primary : (int8_t)primaryIndex
};

View File

@ -577,6 +577,9 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan) const
if (filterStatus.flags.pred_horiz_pos_abs) {
flags |= EKF_PRED_POS_HORIZ_ABS;
}
if (!filterStatus.flags.initalized) {
flags |= EKF_UNINITIALIZED;
}
// get variances
float velVar, posVar, hgtVar, tasVar;