Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Request timed up parameters as soon as possible #1136

Merged
merged 4 commits into from
Jan 16, 2019
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 17 additions & 5 deletions mavros/src/plugins/param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -424,6 +424,7 @@ class ParamPlugin : public plugin::PluginBase {
IDLE,
RXLIST,
RXPARAM,
RXPARAM_TIMEDOUT,
TXPARAM
};
PR param_state;
Expand Down Expand Up @@ -487,8 +488,8 @@ class ParamPlugin : public plugin::PluginBase {
ROS_DEBUG_STREAM_NAMED("param", "PR: New param " << p.to_string());
}

if (param_state == PR::RXLIST || param_state == PR::RXPARAM || param_state == PR::RXPARAM_TIMEDOUT) {

if (param_state == PR::RXLIST || param_state == PR::RXPARAM) {
// we received first param. setup list timeout
if (param_state == PR::RXLIST) {
param_count = pmsg.param_count;
Expand All @@ -514,8 +515,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();

Expand All @@ -528,6 +535,10 @@ class ParamPlugin : public plugin::PluginBase {
missed);
go_idle();
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);
}
}
}
Expand Down Expand Up @@ -626,7 +637,7 @@ class ParamPlugin : public plugin::PluginBase {
restart_timeout_timer();
param_request_list();
}
else if (param_state == PR::RXPARAM) {
else if (param_state == PR::RXPARAM || param_state == PR::RXPARAM_TIMEDOUT) {
if (parameters_missing_idx.empty()) {
ROS_WARN_NAMED("param", "PR: missing list is clear, but we in RXPARAM state, "
"maybe last rerequest fails. Params missed: %zd",
Expand All @@ -636,6 +647,7 @@ class ParamPlugin : public plugin::PluginBase {
return;
}

param_state = PR::RXPARAM_TIMEDOUT;
uint16_t first_miss_idx = parameters_missing_idx.front();
if (param_rx_retries > 0) {
param_rx_retries--;
Expand Down Expand Up @@ -782,7 +794,7 @@ class ParamPlugin : public plugin::PluginBase {
lock.unlock();
res.success = wait_fetch_all();
}
else if (param_state == PR::RXLIST || param_state == PR::RXPARAM) {
else if (param_state == PR::RXLIST || param_state == PR::RXPARAM || param_state == PR::RXPARAM_TIMEDOUT) {
lock.unlock();
res.success = wait_fetch_all();
}
Expand Down Expand Up @@ -859,7 +871,7 @@ class ParamPlugin : public plugin::PluginBase {
{
unique_lock lock(mutex);

if (param_state == PR::RXLIST || param_state == PR::RXPARAM) {
if (param_state == PR::RXLIST || param_state == PR::RXPARAM || param_state == PR::RXPARAM_TIMEDOUT) {
ROS_ERROR_NAMED("param", "PR: receiving not complete");
return false;
}
Expand Down