From 42383dd6f2969d374d2501c1c8493db94770b07a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 4 Mar 2022 14:29:49 +1100 Subject: [PATCH] ArduSub: 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. --- ArduSub/GCS_Mavlink.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 26e10bdfd7..6105d73ddf 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -154,7 +154,7 @@ void GCS_MAVLINK_Sub::send_pid_tuning() const Vector3f &gyro = ahrs.get_gyro(); if (g.gcs_pid_mask & 1) { - const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_roll_pid().get_pid_info(); + const AP_PIDInfo &pid_info = attitude_control.get_rate_roll_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL, pid_info.target*0.01f, degrees(gyro.x), @@ -169,7 +169,7 @@ void GCS_MAVLINK_Sub::send_pid_tuning() } } if (g.gcs_pid_mask & 2) { - const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info(); + const AP_PIDInfo &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH, pid_info.target*0.01f, degrees(gyro.y), @@ -184,7 +184,7 @@ void GCS_MAVLINK_Sub::send_pid_tuning() } } if (g.gcs_pid_mask & 4) { - const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info(); + const AP_PIDInfo &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW, pid_info.target*0.01f, degrees(gyro.z), @@ -199,7 +199,7 @@ void GCS_MAVLINK_Sub::send_pid_tuning() } } if (g.gcs_pid_mask & 8) { - const AP_Logger::PID_Info &pid_info = sub.pos_control.get_accel_z_pid().get_pid_info(); + const AP_PIDInfo &pid_info = sub.pos_control.get_accel_z_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ, pid_info.target*0.01f, -(ahrs.get_accel_ef_blended().z + GRAVITY_MSS),