mirror of https://github.com/ArduPilot/ardupilot
Plane: use AHRS view for all vtol modes
This commit is contained in:
parent
d78275c0a3
commit
ffc94f19cd
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue