Browse Source

AP_Math: added fill_nanf()

used in SITL to invalidate memory
master
Andrew Tridgell 5 years ago
parent
commit
9b746b89db
  1. 8
      libraries/AP_Math/AP_Math.cpp
  2. 3
      libraries/AP_Math/AP_Math.h

8
libraries/AP_Math/AP_Math.cpp

@ -303,3 +303,11 @@ bool rotation_equal(enum Rotation r1, enum Rotation r2)
return (v1 - v2).length() < 0.001; 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");
}
}

3
libraries/AP_Math/AP_Math.h

@ -281,3 +281,6 @@ bool is_valid_octal(uint16_t octal) WARN_IF_UNUSED;
// 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;
// fill an array of float with NaN, used to invalidate memory in SITL
void fill_nanf(float *f, uint16_t count);

Loading…
Cancel
Save