Browse Source

AP_Math: make fill_nanf() use a signalling NaN

we want use of these values to trigger a FPE
master
Andrew Tridgell 5 years ago
parent
commit
66b4e92444
  1. 4
      libraries/AP_Math/AP_Math.cpp
  2. 3
      libraries/AP_Math/AP_Math.h

4
libraries/AP_Math/AP_Math.cpp

@ -339,10 +339,12 @@ bool rotation_equal(enum Rotation r1, enum Rotation r2) @@ -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<float>::signaling_NaN();
}
}
#endif

3
libraries/AP_Math/AP_Math.h

@ -277,5 +277,8 @@ Vector3f rand_vec3f(void); @@ -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

Loading…
Cancel
Save