mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_NavEKF2: setTakeoffExpected and setTouchdownExpected loop through instances
This commit is contained in:
parent
ec5c460584
commit
8baf064317
@ -938,7 +938,9 @@ void NavEKF2::getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, fl
|
||||
void NavEKF2::setTakeoffExpected(bool val)
|
||||
{
|
||||
if (core) {
|
||||
core[primary].setTakeoffExpected(val);
|
||||
for (uint8_t i=0; i<num_cores; i++) {
|
||||
core[i].setTakeoffExpected(val);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -947,7 +949,9 @@ void NavEKF2::setTakeoffExpected(bool val)
|
||||
void NavEKF2::setTouchdownExpected(bool val)
|
||||
{
|
||||
if (core) {
|
||||
core[primary].setTouchdownExpected(val);
|
||||
for (uint8_t i=0; i<num_cores; i++) {
|
||||
core[i].setTouchdownExpected(val);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user