From 27e64149f0f81d288bdc9c837eee5335d961cb89 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 7 Jan 2018 17:16:00 +0100 Subject: [PATCH] MAVLink app: Avoid comparing to zero for value change No functional change, but this avoids numerical issues in the check routine. Since the routine will tend to false positives, we will tend to send more param updates than required in case of numerical noise of the float representation. This is desired, as we prefer to send two updates rather than not sending one. --- src/modules/mavlink/mavlink_parameters.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index 5ddfc18280..4cebb8f3dc 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -155,7 +155,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) param_set(param, &(set.param_value)); // Check if the parameter changed. If it didn't change, send current value back - if ((curr_val - set.param_value) == 0.0f) { + if (!(fabsf(curr_val - set.param_value) > 0.0f)) { send_param(param); } }