mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_NavEKF2: remove getFilterTimeouts access methods
This commit is contained in:
parent
30836535d0
commit
445a461f12
@ -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
|
||||
*/
|
||||
|
@ -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
|
||||
|
@ -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{
|
||||
|
@ -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
|
||||
{
|
||||
|
@ -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
|
||||
*/
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user