Browse Source

Copter: landing gear position set less often

This change means no pwm output is sent to the landing gear servos until the pilot has moved the switch
master
Randy Mackay 8 years ago
parent
commit
a5ea9420c0
  1. 2
      ArduCopter/crash_check.cpp
  2. 12
      ArduCopter/landing_gear.cpp
  3. 8
      ArduCopter/switches.cpp

2
ArduCopter/crash_check.cpp

@ -146,7 +146,7 @@ void Copter::parachute_release() @@ -146,7 +146,7 @@ void Copter::parachute_release()
parachute.release();
// deploy landing gear
landinggear.set_cmd_mode(LandingGear_Deploy);
landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
}
// parachute_manual_release - trigger the release of the parachute, after performing some checks for pilot error

12
ArduCopter/landing_gear.cpp

@ -2,13 +2,13 @@ @@ -2,13 +2,13 @@
// Run landing gear controller at 10Hz
void Copter::landinggear_update(){
void Copter::landinggear_update()
{
// If landing gear control is active, run update function.
if (check_if_auxsw_mode_used(AUXSW_LANDING_GEAR)){
// last status (deployed or retracted) used to check for changes
static bool last_deploy_status;
// last status (deployed or retracted) used to check for changes, initialised to startup state of landing gear
static bool last_deploy_status = landinggear.deployed();
// if we are doing an automatic landing procedure, force the landing gear to deploy.
// To-Do: should we pause the auto-land procedure to give time for gear to come down?
@ -16,11 +16,9 @@ void Copter::landinggear_update(){ @@ -16,11 +16,9 @@ void Copter::landinggear_update(){
(control_mode == RTL && (rtl_state == RTL_LoiterAtHome || rtl_state == RTL_Land || rtl_state == RTL_FinalDescent)) ||
(control_mode == AUTO && auto_mode == Auto_Land) ||
(control_mode == AUTO && auto_mode == Auto_RTL && (rtl_state == RTL_LoiterAtHome || rtl_state == RTL_Land || rtl_state == RTL_FinalDescent))) {
landinggear.force_deploy(true);
landinggear.set_position(AP_LandingGear::LandingGear_Deploy_And_Keep_Deployed);
}
landinggear.update();
// send event message to datalog if status has changed
if (landinggear.deployed() != last_deploy_status){
if (landinggear.deployed()) {

8
ArduCopter/switches.cpp

@ -191,7 +191,6 @@ void Copter::init_aux_switch_function(int8_t ch_option, uint8_t ch_flag) @@ -191,7 +191,6 @@ void Copter::init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
case AUXSW_MISSION_RESET:
case AUXSW_ATTCON_FEEDFWD:
case AUXSW_ATTCON_ACCEL_LIM:
case AUXSW_LANDING_GEAR:
case AUXSW_MOTOR_ESTOP:
case AUXSW_MOTOR_INTERLOCK:
case AUXSW_AVOID_ADSB:
@ -492,13 +491,10 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag) @@ -492,13 +491,10 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
case AUXSW_LANDING_GEAR:
switch (ch_flag) {
case AUX_SWITCH_LOW:
landinggear.set_cmd_mode(LandingGear_Deploy);
break;
case AUX_SWITCH_MIDDLE:
landinggear.set_cmd_mode(LandingGear_Auto);
landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
break;
case AUX_SWITCH_HIGH:
landinggear.set_cmd_mode(LandingGear_Retract);
landinggear.set_position(AP_LandingGear::LandingGear_Retract);
break;
}
break;

Loading…
Cancel
Save