We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent 3a6056f commit e15c638Copy full SHA for e15c638
libraries/GCS_MAVLink/GCS_Param.cpp
@@ -281,15 +281,7 @@ void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg)
281
282
float old_value = vp->cast_to_float(var_type);
283
284
- if (parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) {
285
- // the user can set BRD_OPTIONS to enable set of internal
286
- // parameters, for developer testing or unusual use cases
287
- if (AP_BoardConfig::allow_set_internal_parameters()) {
288
- parameter_flags &= ~AP_PARAM_FLAG_INTERNAL_USE_ONLY;
289
- }
290
291
-
292
- if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) {
+ if (!vp->allow_set_via_mavlink(parameter_flags)) {
293
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Param write denied (%s)", key);
294
// send the readonly value
295
send_parameter_value(key, var_type, old_value);
0 commit comments