mirror of https://github.com/ArduPilot/ardupilot
Rover: failsafe check format fix
adding some brackets perhaps makes it a little clearer
This commit is contained in:
parent
006004be13
commit
9456fe4d70
|
@ -64,10 +64,10 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
|
|||
|
||||
failsafe.triggered &= failsafe.bits;
|
||||
|
||||
if (failsafe.triggered == 0 &&
|
||||
failsafe.bits != 0 &&
|
||||
millis() - failsafe.start_time > g.fs_timeout * 1000 &&
|
||||
control_mode != &mode_rtl &&
|
||||
if ((failsafe.triggered == 0) &&
|
||||
(failsafe.bits != 0) &&
|
||||
(millis() - failsafe.start_time > g.fs_timeout * 1000) &&
|
||||
(control_mode != &mode_rtl) &&
|
||||
((control_mode != &mode_hold || (g2.fs_options & (uint32_t)Failsafe_Options::Failsafe_Option_Active_In_Hold)))) {
|
||||
failsafe.triggered = failsafe.bits;
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe trigger 0x%x", (unsigned int)failsafe.triggered);
|
||||
|
|
Loading…
Reference in New Issue