AP_Math: added rand_float()
This commit is contained in:
parent
c1b6684b9f
commit
2fcecaa7c5
@ -211,3 +211,11 @@ uint16_t get_random16(void)
|
|||||||
return ((m_z << 16) + m_w) & 0xFFFF;
|
return ((m_z << 16) + m_w) & 0xFFFF;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
// generate a random float between -1 and 1, for use in SITL
|
||||||
|
float rand_float(void)
|
||||||
|
{
|
||||||
|
return ((((unsigned)random()) % 2000000) - 1.0e6) / 1.0e6;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
@ -221,3 +221,6 @@ float linear_interpolate(float low_output, float high_output,
|
|||||||
/* simple 16 bit random number generator */
|
/* simple 16 bit random number generator */
|
||||||
uint16_t get_random16(void);
|
uint16_t get_random16(void);
|
||||||
|
|
||||||
|
// generate a random float between -1 and 1, for use in SITL
|
||||||
|
float rand_float(void);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user