Browse Source

AP_NavEKF2: setTakeoffExpected and setTouchdownExpected loop through instances

master
Jonathan Challinger 9 years ago committed by Andrew Tridgell
parent
commit
8baf064317
  1. 8
      libraries/AP_NavEKF2/AP_NavEKF2.cpp

8
libraries/AP_NavEKF2/AP_NavEKF2.cpp

@ -938,7 +938,9 @@ void NavEKF2::getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, fl @@ -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) @@ -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…
Cancel
Save