AP_InertialSensor: fix externalAHRS detection
'A = B >= C' kind. The expression is calculated as following: 'A = (B >= C)'
This commit is contained in:
parent
ae11353d81
commit
29b13ff98a
@ -940,7 +940,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
|
||||
|
Loading…
Reference in New Issue
Block a user