diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 07a23adeb3..6a2c762c2b 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -290,7 +290,7 @@ void GCS_MAVLINK_Plane::send_wind() const } // sends a single pid info over the provided channel -void GCS_MAVLINK_Plane::send_pid_info(const AP_Logger::PID_Info *pid_info, +void GCS_MAVLINK_Plane::send_pid_info(const AP_PIDInfo *pid_info, const uint8_t axis, const float achieved) { if (pid_info == nullptr) { @@ -322,7 +322,7 @@ void GCS_MAVLINK_Plane::send_pid_tuning() const Parameters &g = plane.g; - const AP_Logger::PID_Info *pid_info; + const AP_PIDInfo *pid_info; if (g.gcs_pid_mask & TUNING_BITS_ROLL) { pid_info = &plane.rollController.get_pid_info(); #if HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 95fa3bca64..8518baccf5 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -41,7 +41,7 @@ protected: private: - void send_pid_info(const AP_Logger::PID_Info *pid_info, const uint8_t axis, const float achieved); + void send_pid_info(const AP_PIDInfo *pid_info, const uint8_t axis, const float achieved); void handleMessage(const mavlink_message_t &msg) override; bool handle_guided_request(AP_Mission::Mission_Command &cmd) override; diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 33bbc2296b..9bd0fa9e27 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -18,6 +18,7 @@ #include #include #include +#include #include #include "qautotune.h" #include "defines.h"