Plane: use AHRS view for all vtol modes

This commit is contained in:
IamPete1 2019-03-14 17:41:26 +00:00 committed by Andrew Tridgell
parent d78275c0a3
commit ffc94f19cd
1 changed files with 1 additions and 1 deletions

View File

@ -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;