From e57e9da4b40efd52e64e2053868d681f5a734a88 Mon Sep 17 00:00:00 2001 From: angri Date: Mon, 14 Jan 2019 19:50:36 +0300 Subject: [PATCH] plugin:param added logging regarding rerequests --- mavros/src/plugins/param.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/mavros/src/plugins/param.cpp b/mavros/src/plugins/param.cpp index 50556382f..5d772203b 100644 --- a/mavros/src/plugins/param.cpp +++ b/mavros/src/plugins/param.cpp @@ -489,8 +489,14 @@ class ParamPlugin : public plugin::PluginBase { parameters_missing_idx.remove(pmsg.param_index); // in receiving mode we use param_rx_retries for LIST and PARAM - if (it_is_first_requested) + if (it_is_first_requested) { + ROS_DEBUG_NAMED("param", "PR: got a value of a requested param idx=%u, " + "resetting retries count", pmsg.param_index); param_rx_retries = RETRIES_COUNT; + } else if (param_state == PR::RXPARAM_TIMEDOUT) { + ROS_INFO_NAMED("param", "PR: got an unsolicited param value idx=%u, " + "not resetting retries count %zu", pmsg.param_index, param_rx_retries); + } restart_timeout_timer(); @@ -505,6 +511,7 @@ class ParamPlugin : public plugin::PluginBase { list_receiving.notify_all(); } else if (param_state == PR::RXPARAM_TIMEDOUT) { uint16_t first_miss_idx = parameters_missing_idx.front(); + ROS_DEBUG_NAMED("param", "PR: requesting next timed out parameter idx=%u", first_miss_idx); param_request_read("", first_miss_idx); } }