mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: moved LANDING_GEAR to common RC_Channel
This commit is contained in:
parent
f89c770c46
commit
637dc718df
@ -95,7 +95,6 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_
|
||||
case THROW:
|
||||
case SMART_RTL:
|
||||
case GUIDED:
|
||||
case LANDING_GEAR:
|
||||
case PARACHUTE_RELEASE:
|
||||
case ARMDISARM:
|
||||
case WINCH_CONTROL:
|
||||
@ -351,20 +350,6 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
||||
#endif
|
||||
break;
|
||||
|
||||
case LANDING_GEAR:
|
||||
switch (ch_flag) {
|
||||
case LOW:
|
||||
copter.landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
|
||||
break;
|
||||
case MIDDLE:
|
||||
// nothing
|
||||
break;
|
||||
case HIGH:
|
||||
copter.landinggear.set_position(AP_LandingGear::LandingGear_Retract);
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case MOTOR_ESTOP:
|
||||
// Turn on Emergency Stop logic when channel is high
|
||||
copter.set_motor_emergency_stop(ch_flag == HIGH);
|
||||
|
@ -46,7 +46,6 @@ LIBRARIES += AP_BattMonitor
|
||||
LIBRARIES += AP_BoardConfig
|
||||
LIBRARIES += AP_Frsky_Telem
|
||||
LIBRARIES += AP_Parachute
|
||||
LIBRARIES += AP_LandingGear
|
||||
LIBRARIES += AP_Terrain
|
||||
LIBRARIES += AP_RPM
|
||||
LIBRARIES += AC_PrecLand
|
||||
|
@ -18,7 +18,6 @@ def build(bld):
|
||||
'AP_Camera',
|
||||
'AP_IRLock',
|
||||
'AP_InertialNav',
|
||||
'AP_LandingGear',
|
||||
'AP_Motors',
|
||||
'AP_Parachute',
|
||||
'AP_RCMapper',
|
||||
|
Loading…
Reference in New Issue
Block a user