Browse Source

AP_LANDING_GEAR: Remove deploy lock

Since the RC switches only respond to changes, there is no longer a need
for this lock state. The gear can be retracted or deployed by RC switch,
flight mode, or mavlink command freely without convoluted unlocking
methods.  Also removed use of this in the associated Copter code.
mission-4.1.18
Matt 7 years ago committed by Randy Mackay
parent
commit
15823d9e97
  1. 2
      ArduCopter/landing_gear.cpp
  2. 7
      libraries/AP_LandingGear/AP_LandingGear.cpp
  3. 2
      libraries/AP_LandingGear/AP_LandingGear.h

2
ArduCopter/landing_gear.cpp

@ -15,7 +15,7 @@ void Copter::landinggear_update()
// if we are doing an automatic landing procedure, force the landing gear to deploy. // 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? // To-Do: should we pause the auto-land procedure to give time for gear to come down?
if (flightmode->landing_gear_should_be_deployed()) { if (flightmode->landing_gear_should_be_deployed()) {
landinggear.set_position(AP_LandingGear::LandingGear_Deploy_And_Keep_Deployed); landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
} }
// send event message to datalog if status has changed // send event message to datalog if status has changed

7
libraries/AP_LandingGear/AP_LandingGear.cpp

@ -58,17 +58,10 @@ void AP_LandingGear::set_position(LandingGearCommand cmd)
{ {
switch (cmd) { switch (cmd) {
case LandingGear_Retract: case LandingGear_Retract:
if (!_deploy_lock) {
retract(); retract();
}
break; break;
case LandingGear_Deploy: case LandingGear_Deploy:
deploy(); deploy();
_deploy_lock = false;
break;
case LandingGear_Deploy_And_Keep_Deployed:
deploy();
_deploy_lock = true;
break; break;
} }
} }

2
libraries/AP_LandingGear/AP_LandingGear.h

@ -25,7 +25,6 @@ public:
enum LandingGearCommand { enum LandingGearCommand {
LandingGear_Retract, LandingGear_Retract,
LandingGear_Deploy, LandingGear_Deploy,
LandingGear_Deploy_And_Keep_Deployed,
}; };
// Gear command modes // Gear command modes
@ -54,7 +53,6 @@ private:
// internal variables // internal variables
bool _deployed; // true if the landing gear has been deployed, initialized false bool _deployed; // true if the landing gear has been deployed, initialized false
bool _deploy_lock; // used to force landing gear to remain deployed until another regular Deploy command is received to reduce accidental retraction
/// retract - retract landing gear /// retract - retract landing gear
void retract(); void retract();

Loading…
Cancel
Save