Browse Source

AC_AttitudeControl: stop libraries including AP_Logger.h in .h files

AP_Logger.h is a nexus of includes; while this is being improved over
time, there's no reason for the library headers to include AP_Logger.h
as the logger itself is access by singleton and the structures are in
LogStructure.h

This necessitated moving The PID_Info structure out of AP_Logger's
namespace.  This cleans up a pretty nasty bit - that structure is
definitely not simply used for logging, but also used to pass pid
information around to controllers!

There are a lot of patches in here because AP_Logger.h, acting as a
nexus, was providing transitive header file inclusion in many (some
unlikely!) places.
apm_2208
Peter Barker 3 years ago committed by Peter Barker
parent
commit
c1e776fc46
  1. 7
      libraries/AC_AttitudeControl/ControlMonitor.cpp

7
libraries/AC_AttitudeControl/ControlMonitor.cpp

@ -1,6 +1,7 @@
#include "AC_AttitudeControl.h" #include "AC_AttitudeControl.h"
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_Logger/AP_Logger.h>
/* /*
code to monitor and report on the rate controllers, allowing for 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) 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.P + iroll.FF, _control_monitor.rms_roll_P);
control_monitor_filter_pid(iroll.D, _control_monitor.rms_roll_D); 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.P + ipitch.FF, _control_monitor.rms_pitch_P);
control_monitor_filter_pid(ipitch.D, _control_monitor.rms_pitch_D); 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); control_monitor_filter_pid(iyaw.P + iyaw.D + iyaw.FF, _control_monitor.rms_yaw);
} }

Loading…
Cancel
Save