mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Simplify boolean expression
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
4f81aa82e2
commit
3b0dac3198
|
@ -90,11 +90,7 @@ void NavEKF3_core::setWindMagStateLearningMode()
|
|||
}
|
||||
|
||||
// determine if the vehicle is manoeuvring
|
||||
if (accNavMagHoriz > 0.5f) {
|
||||
manoeuvring = true;
|
||||
} else {
|
||||
manoeuvring = false;
|
||||
}
|
||||
manoeuvring = accNavMagHoriz > 0.5f;
|
||||
|
||||
// Determine if learning of magnetic field states has been requested by the user
|
||||
bool magCalRequested =
|
||||
|
|
Loading…
Reference in New Issue