mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: fix externalAHRS detection
'A = B >= C' kind. The expression is calculated as following: 'A = (B >= C)'
This commit is contained in:
parent
2361707133
commit
adb82e13ee
@ -1206,7 +1206,8 @@ void Compass::_probe_external_i2c_compasses(void)
|
||||
void Compass::_detect_backends(void)
|
||||
{
|
||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
||||
if (int8_t serial_port = AP::externalAHRS().get_port() >= 0) {
|
||||
const int8_t serial_port = AP::externalAHRS().get_port();
|
||||
if (serial_port >= 0) {
|
||||
ADD_BACKEND(DRIVER_SERIAL, new AP_Compass_ExternalAHRS(serial_port));
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user