AP_LandingGear: Remove deploy_lock state

This commit is contained in:
Matt 2018-08-31 09:41:52 -04:00 committed by Randy Mackay
parent c85496e782
commit 6fda807e49
2 changed files with 1 additions and 10 deletions

View File

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

View File

@ -25,7 +25,6 @@ public:
enum LandingGearCommand {
LandingGear_Retract,
LandingGear_Deploy,
LandingGear_Deploy_And_Keep_Deployed,
};
// Gear command modes
@ -54,7 +53,6 @@ private:
// internal variables
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
void retract();