mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_Compass: Do not use is_zero() for non-float types
This commit is contained in:
parent
7ff8004f8f
commit
f8540f1a80
@ -241,7 +241,7 @@ bool AP_Compass_LSM303D::_read_sample()
|
||||
return false;
|
||||
}
|
||||
|
||||
if (is_zero(rx.x) && is_zero(rx.y) && is_zero(rx.z)) {
|
||||
if (rx.x == 0 && rx.y == 0 && rx.z == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user