mirror of https://github.com/ArduPilot/ardupilot
AP_Math: added fill_nanf()
used in SITL to invalidate memory
This commit is contained in:
parent
5aaeaaea8c
commit
9b746b89db
|
@ -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");
|
||||
}
|
||||
}
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue