mirror of https://github.com/ArduPilot/ardupilot
AP_LandingGear: Remove deploy_lock state
This commit is contained in:
parent
c85496e782
commit
6fda807e49
|
@ -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;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -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…
Reference in New Issue