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),