mirror of https://github.com/ArduPilot/ardupilot
Plane: prevent jump to Circle upon Takeoff mode entry unless flying >10s
This commit is contained in:
parent
6c6998c48a
commit
79ab2179c9
|
@ -65,7 +65,7 @@ void ModeTakeoff::update()
|
||||||
{
|
{
|
||||||
if (!takeoff_started) {
|
if (!takeoff_started) {
|
||||||
// see if we will skip takeoff as already flying
|
// see if we will skip takeoff as already flying
|
||||||
if (plane.is_flying() && plane.ahrs.groundspeed() > 3) {
|
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && plane.ahrs.groundspeed() > 3) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff skipped - circling");
|
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff skipped - circling");
|
||||||
plane.prev_WP_loc = plane.current_loc;
|
plane.prev_WP_loc = plane.current_loc;
|
||||||
plane.next_WP_loc = plane.current_loc;
|
plane.next_WP_loc = plane.current_loc;
|
||||||
|
|
Loading…
Reference in New Issue