mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Math: remove normalization of random compass Vector3f
This commit is contained in:
parent
406119ed41
commit
fffad18324
@ -348,17 +348,14 @@ float rand_float(void)
|
||||
#endif
|
||||
}
|
||||
|
||||
// generate a random Vector3f with each value between -1.0 and 1.0
|
||||
Vector3f rand_vec3f(void)
|
||||
{
|
||||
Vector3f v {
|
||||
return Vector3f{
|
||||
rand_float(),
|
||||
rand_float(),
|
||||
rand_float()
|
||||
};
|
||||
if (!v.is_zero()) {
|
||||
v.normalize();
|
||||
}
|
||||
return v;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -325,7 +325,7 @@ uint16_t get_random16(void);
|
||||
// generate a random float between -1 and 1, for use in SITL
|
||||
float rand_float(void);
|
||||
|
||||
// generate a random Vector3f of size 1
|
||||
// generate a random Vector3f with each value between -1.0 and 1.0
|
||||
Vector3f rand_vec3f(void);
|
||||
|
||||
// return true if two rotations are equal
|
||||
|
Loading…
Reference in New Issue
Block a user