diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index 887a6747b6..a2951c9665 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -305,3 +305,12 @@ bool rotation_equal(enum Rotation r1, enum Rotation r2) return (v1 - v2).length() < 0.001; } +#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++ = std::numeric_limits::signaling_NaN(); + } +} +#endif diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index 3f841ceba9..feff4f1afb 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -274,3 +274,8 @@ 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; + +#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