mirror of https://github.com/ArduPilot/ardupilot
APM: ensure takeoff_complete is reset
This commit is contained in:
parent
cf432c0ae0
commit
487b909189
|
@ -8,9 +8,16 @@ handle_process_nav_cmd()
|
|||
{
|
||||
// reset navigation integrators
|
||||
// -------------------------
|
||||
land_complete = false;
|
||||
reset_I();
|
||||
|
||||
|
||||
// set land_complete to false to stop us zeroing the throttle
|
||||
land_complete = false;
|
||||
|
||||
// set takeoff_complete to true so we don't add extra evevator
|
||||
// except in a takeoff
|
||||
takeoff_complete = true;
|
||||
|
||||
gcs_send_text_fmt(PSTR("Executing nav command ID #%i"),next_nav_command.id);
|
||||
switch(next_nav_command.id) {
|
||||
|
||||
|
|
Loading…
Reference in New Issue