diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index 08d0e2e901..b853648c22 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -149,15 +149,9 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) _mavlink->send_statustext_info(buf); } else { - // Load current value before setting it - float curr_val; - param_get(param, &curr_val); + // According to the mavlink spec we should always acknowledge a write operation. param_set(param, &(set.param_value)); - - // Check if the parameter changed. If it didn't change, send current value back - if (!(fabsf(curr_val - set.param_value) > 0.0f)) { - send_param(param); - } + send_param(param); } }