mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: fix externalAHRS detection
'A = B >= C' kind. The expression is calculated as following: 'A = (B >= C)'
This commit is contained in:
parent
17cdb07bd5
commit
4481bc6147
|
@ -1208,7 +1208,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