mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Math: bug fix to wrap_360 and wrap_180
angles above 720deg and below 3200deg might not have been properly wrapped. wrap_360_cd could return 36000 when really this should be wrapped back to zero.
This commit is contained in:
parent
e42a10a764
commit
a963ec7e3b
@ -160,8 +160,8 @@ int32_t wrap_360_cd(int32_t error)
|
||||
// for very large numbers use modulus
|
||||
error = error % 36000;
|
||||
}
|
||||
if (error > 36000) error -= 36000;
|
||||
if (error < 0) error += 36000;
|
||||
while (error >= 36000) error -= 36000;
|
||||
while (error < 0) error += 36000;
|
||||
return error;
|
||||
}
|
||||
|
||||
@ -174,8 +174,8 @@ int32_t wrap_180_cd(int32_t error)
|
||||
// for very large numbers use modulus
|
||||
error = error % 36000;
|
||||
}
|
||||
if (error > 18000) { error -= 36000; }
|
||||
if (error < -18000) { error += 36000; }
|
||||
while (error > 18000) { error -= 36000; }
|
||||
while (error < -18000) { error += 36000; }
|
||||
return error;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user