mirror of https://github.com/ArduPilot/ardupilot
remove BROKEN_SLIDER code
use the new CLI_SLIDER_ENABLED option and the "hit ENTER 3 times" method
This commit is contained in:
parent
36923c0996
commit
d2f4fea58a
|
@ -7,8 +7,6 @@
|
|||
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
||||
//#define HIL_MODE HIL_MODE_ATTITUDE
|
||||
|
||||
//#define BROKEN_SLIDER 0 // 1 = yes (use Yaw to enter CLI mode)
|
||||
|
||||
#define FRAME_CONFIG QUAD_FRAME
|
||||
/*
|
||||
options:
|
||||
|
|
|
@ -793,10 +793,6 @@
|
|||
# define CUT_MOTORS 1 // do we cut the motors with no throttle?
|
||||
#endif
|
||||
|
||||
#ifndef BROKEN_SLIDER
|
||||
# define BROKEN_SLIDER 0 // 1 = yes (use Yaw to enter CLI mode)
|
||||
#endif
|
||||
|
||||
#ifndef MOTOR_LEDS
|
||||
# define MOTOR_LEDS 1 // 0 = off, 1 = on
|
||||
#endif
|
||||
|
|
|
@ -568,36 +568,12 @@ init_throttle_cruise()
|
|||
}
|
||||
}
|
||||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
#if BROKEN_SLIDER == 1
|
||||
|
||||
static boolean
|
||||
check_startup_for_CLI()
|
||||
{
|
||||
//return true;
|
||||
if((g.rc_4.radio_max) < 1600){
|
||||
// CLI mode
|
||||
return true;
|
||||
|
||||
}else if(abs(g.rc_4.control_in) > 3000){
|
||||
// CLI mode
|
||||
return true;
|
||||
|
||||
}else{
|
||||
// startup to fly
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
#if CLI_SLIDER_ENABLED == ENABLED && CLI_ENABLED == ENABLED
|
||||
static boolean
|
||||
check_startup_for_CLI()
|
||||
{
|
||||
return (digitalRead(SLIDE_SWITCH_PIN) == 0);
|
||||
}
|
||||
|
||||
#endif // BROKEN_SLIDER
|
||||
#endif // CLI_ENABLED
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue