From d9c82b3bb12496778c5339441af47cf57b46146f Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 4 Sep 2024 10:10:57 +0100 Subject: [PATCH] Plane: Write_Rate() moved to AC_AttitudeControl --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 0a41b5551b6e6e..f4b1b69f6838f4 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1764,7 +1764,7 @@ void QuadPlane::update(void) const bool motors_active = in_vtol_mode() || assisted_flight; if (motors_active && (motors->get_spool_state() != AP_Motors::SpoolState::SHUT_DOWN)) { // log RATE at main loop rate - ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control); + attitude_control->Write_Rate(*motors, *pos_control); // log CTRL and MOTB at 10 Hz if (now - last_ctrl_log_ms > 100) {