Copter: Beeping when first reaching waypoint while in holding there

This commit is contained in:
apinxiko 2018-06-04 12:42:43 +09:00 committed by Randy Mackay
parent 5df4b9f6fd
commit e440583a7c

View File

@ -1792,7 +1792,6 @@ bool Copter::ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
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);
}
}
@ -1809,8 +1808,6 @@ bool Copter::ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
}
}
// verify_circle - check if we have circled the point enough
bool Copter::ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd)
{
@ -1841,8 +1838,6 @@ bool Copter::ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd)
return fabsf(copter.circle_nav->get_angle_total()/M_2PI) >= LOWBYTE(cmd.p1);
}
// verify_spline_wp - check if we have reached the next way point using spline
bool Copter::ModeAuto::verify_spline_wp(const AP_Mission::Mission_Command& cmd)
{