mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: Use landinggear.force_deploy method when auto-landing
This commit is contained in:
parent
20fce5c9ff
commit
62b5f32643
@ -9,6 +9,12 @@ static void landinggear_update(){
|
||||
// last status (deployed or retracted) used to check for changes
|
||||
static bool last_deploy_status;
|
||||
|
||||
// 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 (control_mode == LAND || (control_mode==RTL && rtl_state == Land) || (control_mode == AUTO && auto_mode == Auto_Land)){
|
||||
landinggear.force_deploy(true);
|
||||
}
|
||||
|
||||
landinggear.update();
|
||||
|
||||
// send event message to datalog if status has changed
|
||||
|
Loading…
Reference in New Issue
Block a user