From 4e731bf4e27f884f1ca00816ea1a4e9a0fcb212d Mon Sep 17 00:00:00 2001 From: Hwurzburg Date: Sat, 2 Oct 2021 05:19:23 -0500 Subject: [PATCH] Plane: add VTOL POS1 notification to QRTL mode --- ArduPlane/quadplane.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 092db24553..54796034d8 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2079,11 +2079,12 @@ void QuadPlane::run_xy_controller(void) */ void QuadPlane::poscontrol_init_approach(void) { + const float dist = plane.current_loc.get_distance(plane.next_WP_loc); if ((options & OPTION_DISABLE_APPROACH) != 0) { // go straight to QPOS_POSITION1 poscontrol.set_state(QPOS_POSITION1); + gcs().send_text(MAV_SEVERITY_INFO,"VTOL Position1 d=%.1f", dist); } else if (poscontrol.get_state() != QPOS_APPROACH) { - const float dist = plane.current_loc.get_distance(plane.next_WP_loc); gcs().send_text(MAV_SEVERITY_INFO,"VTOL approach d=%.1f", dist); poscontrol.set_state(QPOS_APPROACH); poscontrol.thrust_loss_start_ms = 0;