mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Beeping when first reaching waypoint even while in holding there
This commit is contained in:
parent
75c2a2b02a
commit
5df4b9f6fd
@ -1789,12 +1789,19 @@ bool Copter::ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||||||
// start timer if necessary
|
// start timer if necessary
|
||||||
if(loiter_time == 0) {
|
if(loiter_time == 0) {
|
||||||
loiter_time = millis();
|
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
|
// check if timer has run out
|
||||||
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
|
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
|
||||||
|
if(loiter_time_max == 0) {
|
||||||
// play a tone
|
// play a tone
|
||||||
AP_Notify::events.waypoint_complete = 1;
|
AP_Notify::events.waypoint_complete = 1;
|
||||||
|
}
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
|
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
|
||||||
return true;
|
return true;
|
||||||
}else{
|
}else{
|
||||||
|
Loading…
Reference in New Issue
Block a user