Copter: Landing gear - remove deploy_lock state

This commit is contained in:
Matt 2018-08-31 09:44:21 -04:00 committed by Randy Mackay
parent 6fda807e49
commit 837903a2bf

View File

@ -15,7 +15,7 @@ void Copter::landinggear_update()
// 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?
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