AP_Math: make fill_nanf() use a signalling NaN
we want use of these values to trigger a FPE
This commit is contained in:
parent
f79907bd1e
commit
66b4e92444
@ -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
|
// fill an array of float with NaN, used to invalidate memory in SITL
|
||||||
void fill_nanf(float *f, uint16_t count)
|
void fill_nanf(float *f, uint16_t count)
|
||||||
{
|
{
|
||||||
while (count--) {
|
while (count--) {
|
||||||
*f++ = nanf("fill");
|
*f++ = std::numeric_limits<float>::signaling_NaN();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
@ -277,5 +277,8 @@ Vector3f rand_vec3f(void);
|
|||||||
// return true if two rotations are equal
|
// return true if two rotations are equal
|
||||||
bool rotation_equal(enum Rotation r1, enum Rotation r2) WARN_IF_UNUSED;
|
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
|
// fill an array of float with NaN, used to invalidate memory in SITL
|
||||||
void fill_nanf(float *f, uint16_t count);
|
void fill_nanf(float *f, uint16_t count);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user