Plane: if already flying in TAKEOFF mode then skip takeoff

This commit is contained in:
Andrew Tridgell 2019-10-10 13:17:36 +11:00
parent dc2aaa7d5a
commit f628524601
1 changed files with 11 additions and 0 deletions

View File

@ -63,6 +63,17 @@ bool ModeTakeoff::_enter()
void ModeTakeoff::update()
{
if (!takeoff_started) {
// see if we will skip takeoff as already flying
if (plane.is_flying() && plane.ahrs.groundspeed() > 3) {
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff skipped - circling");
plane.prev_WP_loc = plane.current_loc;
plane.next_WP_loc = plane.current_loc;
takeoff_started = true;
plane.set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_NORMAL);
}
}
if (!takeoff_started) {
// setup target location 1.5 times loiter radius from the
// takeoff point, at a height of TKOFF_ALT