diff --git a/libraries/AC_AutoTune/AC_AutoTune.cpp b/libraries/AC_AutoTune/AC_AutoTune.cpp index 64dafeab8e..213ae21551 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune.cpp @@ -443,7 +443,7 @@ void AC_AutoTune::control_attitude() #if HAL_LOGGING_ENABLED // log this iterations lean angle and rotation rate Log_AutoTuneDetails(); - ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control); + attitude_control->Write_Rate(*pos_control); log_pids(); #endif