diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 8ba9c06595..c4b66a7edd 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1772,6 +1772,10 @@ void QuadPlane::update(void) if (motors->armed()) { const bool motors_active = in_vtol_mode() || assisted_flight; if (motors_active && (motors->get_spool_state() != AP_Motors::SpoolState::SHUT_DOWN)) { + // log ANG at main loop rate + if (show_vtol_view()) { + attitude_control->Write_ANG(); + } // log RATE at main loop rate attitude_control->Write_Rate(*pos_control);