From 66b4e924445f4c97327e8abc6a81059da2464e7e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 28 Sep 2019 17:31:46 +1000 Subject: [PATCH] AP_Math: make fill_nanf() use a signalling NaN we want use of these values to trigger a FPE --- libraries/AP_Math/AP_Math.cpp | 4 +++- libraries/AP_Math/AP_Math.h | 3 +++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index 000b79ddc4..d621fc2fe1 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -339,10 +339,12 @@ bool rotation_equal(enum Rotation r1, enum Rotation r2) } +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL // fill an array of float with NaN, used to invalidate memory in SITL void fill_nanf(float *f, uint16_t count) { while (count--) { - *f++ = nanf("fill"); + *f++ = std::numeric_limits::signaling_NaN(); } } +#endif diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index fd560dc1b8..8d7b2c5365 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -277,5 +277,8 @@ Vector3f rand_vec3f(void); // return true if two rotations are equal bool rotation_equal(enum Rotation r1, enum Rotation r2) WARN_IF_UNUSED; +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL // fill an array of float with NaN, used to invalidate memory in SITL void fill_nanf(float *f, uint16_t count); +#endif +