From 384571ddf2e70e29f47893283a74dc64c57796cc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 17 Mar 2020 11:30:44 +1100 Subject: [PATCH] GCS_MAVLink: send only old value for readonly param set this prevents a condition where the GCS can display the wrong value if the 2nd PARAM_VALUE is lost Note that groundstations can tell the set failed due to readonly in the following ways: 1) look for the statustext: Param write denied (PARAMNAME) 2) see that the value came back with the old value, with index of 65535 3) can repeat the send, looking for (1) and (2) Michael has proposed we add a PARAM_VALUE mavlink2 flags extension. That would be nice, but we should still make this change to fix the issue with mavlink 1.0 --- libraries/GCS_MAVLink/GCS_Param.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Param.cpp b/libraries/GCS_MAVLink/GCS_Param.cpp index bc65f2529d..e655577a83 100644 --- a/libraries/GCS_MAVLink/GCS_Param.cpp +++ b/libraries/GCS_MAVLink/GCS_Param.cpp @@ -276,10 +276,7 @@ void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg) if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) { gcs().send_text(MAV_SEVERITY_WARNING, "Param write denied (%s)", key); - // echo back the incorrect value so that we fulfull the - // parameter state machine requirements: - send_parameter_value(key, var_type, packet.param_value); - // and then announce what the correct value is: + // send the readonly value send_parameter_value(key, var_type, old_value); return; }