Copter: avoid keeping buzzing while in holding at waypoint

This commit is contained in:
apinxiko 2018-05-25 01:31:01 +09:00 committed by Randy Mackay
parent 938dc2e47d
commit a1fd1cb9b2
1 changed files with 2 additions and 3 deletions

View File

@ -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{