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
This commit is contained in:
Andrew Tridgell 2020-03-17 11:30:44 +11:00
parent 55d37e5d0e
commit 21e93dae34
1 changed files with 1 additions and 4 deletions

View File

@ -278,10 +278,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;
}