From 445a461f12b42b9caef1cfb7018a671e4e5d5743 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 21 Jan 2021 18:02:07 +1100 Subject: [PATCH] AP_NavEKF2: remove getFilterTimeouts access methods --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 21 --------------------- libraries/AP_NavEKF2/AP_NavEKF2.h | 14 -------------- libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp | 9 +++++++-- libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp | 9 --------- libraries/AP_NavEKF2/AP_NavEKF2_core.h | 13 ------------- libraries/AP_NavEKF2/LogStructure.h | 2 +- 6 files changed, 8 insertions(+), 60 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 9d62a3f802..b522315142 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -1307,27 +1307,6 @@ void NavEKF2::getFilterFaults(int8_t instance, uint16_t &faults) const } } -/* - return filter timeout status as a bitmasked integer - 0 = position measurement timeout - 1 = velocity measurement timeout - 2 = height measurement timeout - 3 = magnetometer measurement timeout - 4 = unassigned - 5 = unassigned - 6 = unassigned - 7 = unassigned -*/ -void NavEKF2::getFilterTimeouts(int8_t instance, uint8_t &timeouts) const -{ - if (instance < 0 || instance >= num_cores) instance = primary; - if (core) { - core[instance].getFilterTimeouts(timeouts); - } else { - timeouts = 0; - } -} - /* return filter status flags */ diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index 058134abe9..ee9e1b4f47 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -220,20 +220,6 @@ public: */ void getFilterFaults(int8_t instance, uint16_t &faults) const; - /* - return filter timeout status as a bitmasked integer for the specified instance - An out of range instance (eg -1) returns data for the primary instance - 0 = position measurement timeout - 1 = velocity measurement timeout - 2 = height measurement timeout - 3 = magnetometer measurement timeout - 4 = unassigned - 5 = unassigned - 6 = unassigned - 7 = unassigned - */ - void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const; - /* return filter gps quality check status for the specified instance An out of range instance (eg -1) returns data for the primary instance diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp index dfb7b0d5c3..45eb415d9d 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp @@ -119,13 +119,18 @@ void NavEKF2_core::Log_Write_NKF4(uint64_t time_us) const float tasVar = 0; Vector2f offset; uint16_t _faultStatus=0; - uint8_t timeoutStatus=0; + const uint8_t timeoutStatus = + posTimeout<<0 | + velTimeout<<1 | + hgtTimeout<<2 | + magTimeout<<3 | + tasTimeout<<4; + nav_filter_status solutionStatus {}; nav_gps_status gpsStatus {}; getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); float tempVar = fmaxf(fmaxf(magVar.x,magVar.y),magVar.z); getFilterFaults(_faultStatus); - getFilterTimeouts(timeoutStatus); getFilterStatus(solutionStatus); getFilterGpsStatus(gpsStatus); const struct log_NKF4 pkt4{ diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index f9bd5f5ab1..7b92ad19c1 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -465,15 +465,6 @@ return filter timeout status as a bitmasked integer 6 = unassigned 7 = unassigned */ -void NavEKF2_core::getFilterTimeouts(uint8_t &timeouts) const -{ - timeouts = (posTimeout<<0 | - velTimeout<<1 | - hgtTimeout<<2 | - magTimeout<<3 | - tasTimeout<<4); -} - // Return the navigation filter status message void NavEKF2_core::getFilterStatus(nav_filter_status &status) const { diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index d4ae686498..a8d15296c8 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -234,19 +234,6 @@ public: */ void getFilterFaults(uint16_t &faults) const; - /* - return filter timeout status as a bitmasked integer - 0 = position measurement timeout - 1 = velocity measurement timeout - 2 = height measurement timeout - 3 = magnetometer measurement timeout - 5 = unassigned - 6 = unassigned - 7 = unassigned - 7 = unassigned - */ - void getFilterTimeouts(uint8_t &timeouts) const; - /* return filter gps quality check status */ diff --git a/libraries/AP_NavEKF2/LogStructure.h b/libraries/AP_NavEKF2/LogStructure.h index eb4b97f37b..248413e630 100644 --- a/libraries/AP_NavEKF2/LogStructure.h +++ b/libraries/AP_NavEKF2/LogStructure.h @@ -178,7 +178,7 @@ struct PACKED log_NKF3 { // @Field: OFN: Most recent position recent magnitude (North component) // @Field: OFE: Most recent position recent magnitude (East component) // @Field: FS: Filter fault status -// @Field: TS: Filter timeout status +// @Field: TS: Filter timeout status bitmask (0:position measurement, 1:velocity measurement, 2:height measurement, 3:magnetometer measurement, 4:airspeed measurement) // @Field: SS: Filter solution status // @Field: GPS: Filter GPS status // @Field: PI: Primary core index