From 5df4b9f6fd20727f4f89eb8473d9d2558bf263c4 Mon Sep 17 00:00:00 2001 From: apinxiko Date: Mon, 4 Jun 2018 03:52:28 +0900 Subject: [PATCH] Beeping when first reaching waypoint even while in holding there --- ArduCopter/mode_auto.cpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 43003d07b8..2b7cbe7756 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1789,12 +1789,19 @@ bool Copter::ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd) // start timer if necessary if(loiter_time == 0) { loiter_time = millis(); + if(loiter_time_max > 0) { + // play a tone + AP_Notify::events.waypoint_complete = 1; + gcs().send_text(MAV_SEVERITY_INFO, "Delay in arrival at command #%i",cmd.index); + } } // check if timer has run out if (((millis() - loiter_time) / 1000) >= loiter_time_max) { - // play a tone - AP_Notify::events.waypoint_complete = 1; + if(loiter_time_max == 0) { + // play a tone + AP_Notify::events.waypoint_complete = 1; + } gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index); return true; }else{