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.
This commit is contained in:
Lorenz Meier
2018-01-07 17:16:00 +01:00
parent 7695f79239
commit 27e64149f0

View File

@@ -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);
}
}