mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Math: disable INEXACT flag from Float exception
This commit is contained in:
parent
07907ac81d
commit
05fe49a51f
@ -285,7 +285,8 @@ bool inverse4x4(float m[],float invOut[])
|
||||
uint8_t i;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
int old = fedisableexcept(FE_OVERFLOW);
|
||||
//disable FE_INEXACT detection as it fails on mac os runs
|
||||
int old = fedisableexcept(FE_INEXACT | FE_OVERFLOW);
|
||||
if (old < 0) {
|
||||
hal.console->printf("inverse4x4(): warning: error on disabling FE_OVERFLOW floating point exception\n");
|
||||
}
|
||||
@ -405,12 +406,6 @@ bool inverse4x4(float m[],float invOut[])
|
||||
|
||||
det = m[0] * inv[0] + m[1] * inv[4] + m[2] * inv[8] + m[3] * inv[12];
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
if (old >= 0 && feenableexcept(old) < 0) {
|
||||
hal.console->printf("inverse4x4(): warning: error on restoring floating exception mask\n");
|
||||
}
|
||||
#endif
|
||||
|
||||
if (is_zero(det) || isinf(det)){
|
||||
return false;
|
||||
}
|
||||
@ -419,6 +414,13 @@ bool inverse4x4(float m[],float invOut[])
|
||||
|
||||
for (i = 0; i < 16; i++)
|
||||
invOut[i] = inv[i] * det;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
if (old >= 0 && feenableexcept(old) < 0) {
|
||||
hal.console->printf("inverse4x4(): warning: error on restoring floating exception mask\n");
|
||||
}
|
||||
#endif
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user