From 2170e7eba0a10f239ed4368e64e3a9d511df2b4b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 7 Jan 2018 16:36:47 +0100 Subject: [PATCH] MAVLink main: Only update internal parameters All param handling happens in the param manager. --- src/modules/mavlink/mavlink_main.cpp | 16 +--------------- 1 file changed, 1 insertion(+), 15 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 9f4a769c62..7d96c4962d 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2190,23 +2190,9 @@ Mavlink::task_main(int argc, char *argv[]) update_rate_mult(); - /* param update backoff: update only after 50 ms after the last change */ - param_sub->update(¶m_time, nullptr); - - if (param_time + 100 * 1000 > hrt_absolute_time()) { + if (param_sub->update(¶m_time, nullptr)) { /* parameters updated */ mavlink_update_system(); - /* send out param cache value */ - uint32_t hash = param_hash_check(); - - /* build the one-off response message */ - mavlink_param_value_t param_value; - param_value.param_count = param_count_used(); - param_value.param_index = -1; - strncpy(param_value.param_id, HASH_PARAM, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); - param_value.param_type = MAV_PARAM_TYPE_UINT32; - memcpy(¶m_value.param_value, &hash, sizeof(hash)); - mavlink_msg_param_value_send_struct(get_channel(), ¶m_value); } check_radio_config();