AP_Math: allow rand_float() on STM32

This commit is contained in:
Andrew Tridgell 2024-05-17 11:55:55 +10:00
parent ee6bd4fca0
commit 6de6de694a

View File

@ -339,7 +339,6 @@ uint16_t get_random16(void)
}
#if AP_SIM_ENABLED
// generate a random float between -1 and 1, for use in SITL
float rand_float(void)
{
@ -359,7 +358,6 @@ Vector3f rand_vec3f(void)
rand_float()
};
}
#endif
/*
return true if two rotations are equivalent