diff --git a/libraries/AC_AttitudeControl/ControlMonitor.cpp b/libraries/AC_AttitudeControl/ControlMonitor.cpp index 37fadc2600..5efdb1606c 100644 --- a/libraries/AC_AttitudeControl/ControlMonitor.cpp +++ b/libraries/AC_AttitudeControl/ControlMonitor.cpp @@ -1,6 +1,7 @@ #include "AC_AttitudeControl.h" #include #include +#include /* code to monitor and report on the rate controllers, allowing for @@ -24,15 +25,15 @@ void AC_AttitudeControl::control_monitor_filter_pid(float value, float &rms) */ void AC_AttitudeControl::control_monitor_update(void) { - const AP_Logger::PID_Info &iroll = get_rate_roll_pid().get_pid_info(); + const AP_PIDInfo &iroll = get_rate_roll_pid().get_pid_info(); control_monitor_filter_pid(iroll.P + iroll.FF, _control_monitor.rms_roll_P); control_monitor_filter_pid(iroll.D, _control_monitor.rms_roll_D); - const AP_Logger::PID_Info &ipitch = get_rate_pitch_pid().get_pid_info(); + const AP_PIDInfo &ipitch = get_rate_pitch_pid().get_pid_info(); control_monitor_filter_pid(ipitch.P + ipitch.FF, _control_monitor.rms_pitch_P); control_monitor_filter_pid(ipitch.D, _control_monitor.rms_pitch_D); - const AP_Logger::PID_Info &iyaw = get_rate_yaw_pid().get_pid_info(); + const AP_PIDInfo &iyaw = get_rate_yaw_pid().get_pid_info(); control_monitor_filter_pid(iyaw.P + iyaw.D + iyaw.FF, _control_monitor.rms_yaw); }