mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Math: allow rand_float() on STM32
This commit is contained in:
parent
ee6bd4fca0
commit
6de6de694a
@ -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
|
// generate a random float between -1 and 1, for use in SITL
|
||||||
float rand_float(void)
|
float rand_float(void)
|
||||||
{
|
{
|
||||||
@ -359,7 +358,6 @@ Vector3f rand_vec3f(void)
|
|||||||
rand_float()
|
rand_float()
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
return true if two rotations are equivalent
|
return true if two rotations are equivalent
|
||||||
|
Loading…
Reference in New Issue
Block a user