AP_Math: correct range of returned value for rand_float on real hardware

This commit is contained in:
Peter Barker 2024-08-25 16:08:56 +10:00 committed by Andrew Tridgell
parent 6de6de694a
commit 84bcea73e1

View File

@ -339,13 +339,13 @@ uint16_t get_random16(void)
}
// generate a random float between -1 and 1, for use in SITL
// generate a random float between -1 and 1
float rand_float(void)
{
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
return ((((unsigned)random()) % 2000000) - 1.0e6) / 1.0e6;
#else
return get_random16() / 65535.0;
return (get_random16() / 65535.0) * 2 - 1;
#endif
}