aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_parameters.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mavlink/mavlink_parameters.cpp')
-rw-r--r--src/modules/mavlink/mavlink_parameters.cpp5
1 files changed, 3 insertions, 2 deletions
diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp
index 20d7cfdbb..9c8794017 100644
--- a/src/modules/mavlink/mavlink_parameters.cpp
+++ b/src/modules/mavlink/mavlink_parameters.cpp
@@ -130,7 +130,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
} else {
/* when index is >= 0, send this parameter again */
- send_param(param_for_index(req_read.param_index));
+ send_param(param_for_used_index(req_read.param_index));
}
}
break;
@@ -192,6 +192,7 @@ MavlinkParametersManager::send(const hrt_abstime t)
/* look for the first parameter which is used */
param_t p;
do {
+ /* walk through all parameters, including unused ones */
p = param_for_index(_send_all_index);
_send_all_index++;
} while (p != PARAM_INVALID && !param_used(p));
@@ -200,7 +201,7 @@ MavlinkParametersManager::send(const hrt_abstime t)
send_param(p);
}
- if (_send_all_index >= (int) param_count()) {
+ if ((p == PARAM_INVALID) || (_send_all_index >= (int) param_count())) {
_send_all_index = -1;
}
}