mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: compiler warnings: apply is_zero(float) or is_equal(float)
due to an include cross-dependency between ap_param and ap_math, I punted and reimplemented is_equal() for this one function in the header
This commit is contained in:
parent
bff69de249
commit
440438fdda
@ -735,7 +735,7 @@ bool AP_Param::save(bool force_save)
|
||||
} else {
|
||||
v2 = get_default_value(&info->def_value);
|
||||
}
|
||||
if (v1 == v2 && !force_save) {
|
||||
if (AP_Math::is_equal(v1,v2) && !force_save) {
|
||||
return true;
|
||||
}
|
||||
if (phdr.type != AP_PARAM_INT32 &&
|
||||
@ -1177,7 +1177,7 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info)
|
||||
} else if (ptype <= AP_PARAM_FLOAT && header.type <= AP_PARAM_FLOAT) {
|
||||
// perform scalar->scalar conversion
|
||||
float v = ap->cast_to_float((enum ap_var_type)header.type);
|
||||
if (v != ap2->cast_to_float(ptype)) {
|
||||
if (!AP_Math::is_equal(v,ap2->cast_to_float(ptype))) {
|
||||
// the value needs to change
|
||||
set_value(ptype, ap2, v);
|
||||
ap2->save();
|
||||
|
@ -25,6 +25,8 @@
|
||||
#include <stddef.h>
|
||||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
#include "float.h"
|
||||
|
||||
#include <AP_Progmem.h>
|
||||
#include <../StorageManager/StorageManager.h>
|
||||
@ -421,7 +423,7 @@ public:
|
||||
/// Combined set and save
|
||||
///
|
||||
bool set_and_save(const T &v) {
|
||||
bool force = (_value != v);
|
||||
bool force = fabsf(_value - v) < FLT_EPSILON;
|
||||
set(v);
|
||||
return save(force);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user