Browse Source

APM: ensure takeoff_complete is reset

master
Andrew Tridgell 13 years ago
parent
commit
4668f8b7db
  1. 9
      ArduPlane/commands_logic.pde

9
ArduPlane/commands_logic.pde

@ -8,9 +8,16 @@ handle_process_nav_cmd() @@ -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…
Cancel
Save