From e0fa829665c1b70a889420c7e8801861518b6885 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 8 Aug 2018 13:14:40 +0900 Subject: [PATCH] Rover: pitch PID_TUNING sends degrees also send FF although it is rarely used --- APMrover2/GCS_Mavlink.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 66917b6d5d..80fb7ea19e 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -217,9 +217,9 @@ void Rover::send_pid_tuning(mavlink_channel_t chan) if (g.gcs_pid_mask & 4) { pid_info = &g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH, - pid_info->desired, - ahrs.pitch, - 0, + degrees(pid_info->desired), + degrees(ahrs.pitch), + pid_info->FF, pid_info->P, pid_info->I, pid_info->D);