AP_Math: make fill_nanf() use a signalling NaN

we want use of these values to trigger a FPE
This commit is contained in:
Andrew Tridgell 2019-10-06 08:38:57 +11:00
parent 43df0022e1
commit ee25d05f3c
2 changed files with 14 additions and 0 deletions

View File

@ -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<float>::signaling_NaN();
}
}
#endif

View File

@ -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