From ffc94f19cd7712091a3dcec98946d4e766606e92 Mon Sep 17 00:00:00 2001 From: IamPete1 <33176108+IamPete1@users.noreply.github.com> Date: Thu, 14 Mar 2019 17:41:26 +0000 Subject: [PATCH] Plane: use AHRS view for all vtol modes --- ArduPlane/GCS_Mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 4c6d338cf7..c78fd23249 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -119,7 +119,7 @@ void GCS_MAVLINK_Plane::send_attitude() const float p = ahrs.pitch - radians(plane.g.pitch_trim_cd*0.01f); float y = ahrs.yaw; - if (plane.quadplane.tailsitter_active()) { + if (plane.quadplane.in_vtol_mode()) { r = plane.quadplane.ahrs_view->roll; p = plane.quadplane.ahrs_view->pitch; y = plane.quadplane.ahrs_view->yaw;