From 315c5fb7d74becf54cbaf333e659ca648a4a4b68 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 26 Nov 2021 13:02:20 +0900 Subject: [PATCH] Rover: GCS_PID_MASK supports Velocity North and East --- Rover/GCS_Mavlink.cpp | 34 ++++++++++++++++++++++++++++++++++ Rover/Parameters.cpp | 4 ++-- 2 files changed, 36 insertions(+), 2 deletions(-) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 35790deb80..ff2a1e6fc4 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -288,6 +288,40 @@ void GCS_MAVLINK_Rover::send_pid_tuning() return; } } + + // Position Controller Velocity North PID + if (g.gcs_pid_mask & 64) { + pid_info = &g2.pos_control.get_vel_pid().get_pid_info_x(); + mavlink_msg_pid_tuning_send(chan, 10, + pid_info->target, + pid_info->actual, + pid_info->FF, + pid_info->P, + pid_info->I, + pid_info->D, + pid_info->slew_rate, + pid_info->Dmod); + if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) { + return; + } + } + + // Position Controller Velocity East PID + if (g.gcs_pid_mask & 128) { + pid_info = &g2.pos_control.get_vel_pid().get_pid_info_y(); + mavlink_msg_pid_tuning_send(chan, 11, + pid_info->target, + pid_info->actual, + pid_info->FF, + pid_info->P, + pid_info->I, + pid_info->D, + pid_info->slew_rate, + pid_info->Dmod); + if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) { + return; + } + } } void Rover::send_wheel_encoder_distance(const mavlink_channel_t chan) diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index d4a4f61b64..b67981597e 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -63,8 +63,8 @@ const AP_Param::Info Rover::var_info[] = { // @DisplayName: GCS PID tuning mask // @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for // @User: Advanced - // @Values: 0:None,1:Steering,2:Throttle,4:Pitch,8:Left Wheel,16:Right Wheel,32:Sailboat Heel - // @Bitmask: 0:Steering,1:Throttle,2:Pitch,3:Left Wheel,4:Right Wheel,5:Sailboat Heel + // @Values: 0:None,1:Steering,2:Throttle,4:Pitch,8:Left Wheel,16:Right Wheel,32:Sailboat Heel,64:Velocity North,128:Velocity East + // @Bitmask: 0:Steering,1:Throttle,2:Pitch,3:Left Wheel,4:Right Wheel,5:Sailboat Heel,6:Velocity North,7:Velocity East GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0), // @Param: AUTO_TRIGGER_PIN