From 9b746b89dbe49637b09edfccb9c902ad78671809 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 21 Sep 2019 10:32:54 +1000 Subject: [PATCH] AP_Math: added fill_nanf() used in SITL to invalidate memory --- libraries/AP_Math/AP_Math.cpp | 8 ++++++++ libraries/AP_Math/AP_Math.h | 3 +++ 2 files changed, 11 insertions(+) diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index 3fa8814969..f0baef8a4b 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -303,3 +303,11 @@ bool rotation_equal(enum Rotation r1, enum Rotation r2) return (v1 - v2).length() < 0.001; } + +// 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"); + } +} diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index 618b97ff9a..40d38a0f9c 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -281,3 +281,6 @@ bool is_valid_octal(uint16_t octal) WARN_IF_UNUSED; // return true if two rotations are equal bool rotation_equal(enum Rotation r1, enum Rotation r2) WARN_IF_UNUSED; + +// fill an array of float with NaN, used to invalidate memory in SITL +void fill_nanf(float *f, uint16_t count);