mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: Simplify boolean expression
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
ffe356d597
commit
030b6f2a49
@ -112,11 +112,7 @@ bool Rover::ekf_over_threshold()
|
||||
return true;
|
||||
}
|
||||
|
||||
if (ekf_position_ok()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
return !ekf_position_ok();
|
||||
}
|
||||
|
||||
// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
|
||||
|
@ -49,7 +49,7 @@ void ModeAcro::update()
|
||||
|
||||
bool ModeAcro::requires_velocity() const
|
||||
{
|
||||
return g2.motors.have_skid_steering()? false: true;
|
||||
return !g2.motors.have_skid_steering();
|
||||
}
|
||||
|
||||
// sailboats in acro mode support user manually initiating tacking from transmitter
|
||||
|
Loading…
Reference in New Issue
Block a user