mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_NavEKF3: fixed use of configured() vs configured_in_storage()
This commit is contained in:
parent
aafec1fbe7
commit
d5670ace3b
@ -1609,7 +1609,7 @@ void NavEKF3::writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms,
|
||||
void NavEKF3::convert_parameters()
|
||||
{
|
||||
// exit immediately if param conversion has been done before
|
||||
if (sources.configured_in_storage()) {
|
||||
if (sources.configured()) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -1646,12 +1646,12 @@ void NavEKF3::convert_parameters()
|
||||
case 3:
|
||||
default:
|
||||
// EK3_GPS_TYPE == 3 (No GPS) we don't know what to do, could be optical flow, beacon or external nav
|
||||
sources.mark_configured_in_storage();
|
||||
sources.mark_configured();
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
// mark configured in storage so conversion is only run once
|
||||
sources.mark_configured_in_storage();
|
||||
sources.mark_configured();
|
||||
}
|
||||
|
||||
// use EK3_ALT_SOURCE to set EK3_SRC1_POSZ
|
||||
|
Loading…
Reference in New Issue
Block a user