mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
Plane: reset VTOL takeoff if not armed
we need to reset the takeoff target position while disarmed so we don't use spurious position information from before we get good GPS lock. also remove the "Resetting previous waypoint" message as it doesn't provide useful information and is just a distraction (it would be printed continuously while waiting for arming with this PR)
This commit is contained in:
parent
9ee5912e8b
commit
39d7447695
@ -51,7 +51,6 @@ void Plane::set_next_WP(const struct Location &loc)
|
||||
// location as the previous waypoint, to prevent immediately
|
||||
// considering the waypoint complete
|
||||
if (current_loc.past_interval_finish_line(prev_WP_loc, next_WP_loc)) {
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "Resetting previous waypoint");
|
||||
prev_WP_loc = current_loc;
|
||||
}
|
||||
|
||||
|
@ -3421,9 +3421,10 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd)
|
||||
|
||||
const uint32_t now = millis();
|
||||
|
||||
// reset takeoff start time if we aren't armed, as we won't have made any progress
|
||||
// reset takeoff if we aren't armed
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
takeoff_start_time_ms = now;
|
||||
do_vtol_takeoff(cmd);
|
||||
return false;
|
||||
}
|
||||
|
||||
if (now - takeoff_start_time_ms < 3000 &&
|
||||
|
Loading…
Reference in New Issue
Block a user