diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 16b3ccc48c..43003d07b8 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1786,9 +1786,6 @@ bool Copter::ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd) return false; } - // play a tone - AP_Notify::events.waypoint_complete = 1; - // start timer if necessary if(loiter_time == 0) { loiter_time = millis(); @@ -1796,6 +1793,8 @@ bool Copter::ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd) // check if timer has run out if (((millis() - loiter_time) / 1000) >= loiter_time_max) { + // play a tone + AP_Notify::events.waypoint_complete = 1; gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index); return true; }else{