mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Logic fix for RTL option
This commit is contained in:
parent
020062498b
commit
c143e08d2e
@ -62,7 +62,8 @@ static void read_trim_switch()
|
|||||||
//Serial.println(g.rc_7.control_in, DEC);
|
//Serial.println(g.rc_7.control_in, DEC);
|
||||||
|
|
||||||
#elif CH7_OPTION == CH7_RTL
|
#elif CH7_OPTION == CH7_RTL
|
||||||
set_mode(RTL);
|
if(control_mode != RTL && g.rc_7.control_in > 800)
|
||||||
|
set_mode(RTL);
|
||||||
//do_simple = (g.rc_7.control_in > 800);
|
//do_simple = (g.rc_7.control_in > 800);
|
||||||
//Serial.println(g.rc_7.control_in, DEC);
|
//Serial.println(g.rc_7.control_in, DEC);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user