AP_InertialSensor: fix externalAHRS detection

'A = B >= C' kind. The expression is calculated as following: 'A = (B >= C)'
This commit is contained in:
Pierre Kancir 2021-08-11 00:33:49 +02:00 committed by Randy Mackay
parent 3043ab6b01
commit fad42e8c9c

View File

@ -938,7 +938,8 @@ AP_InertialSensor::detect_backends(void)
#if HAL_EXTERNAL_AHRS_ENABLED
// if enabled, make the first IMU the external AHRS
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(new AP_InertialSensor_ExternalAHRS(*this, serial_port));
}
#endif