diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 1d913aa512..68663a9e24 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -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