diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index e33cce4d3e..8fba42905e 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -912,8 +912,8 @@ AP_InertialSensor::detect_backends(void) _backends_detected = true; -#if defined(HAL_CHIBIOS_ARCH_CUBEBLACK) - // special case for CubeBlack, where the IMUs on the isolated +#if defined(HAL_CHIBIOS_ARCH_CUBE) + // special case for Cubes, where the IMUs on the isolated // board could fail on some boards. If the user has INS_USE=1, // INS_USE2=1 and INS_USE3=0 then force INS_USE3 to 1. This is // done as users loading past parameter files may end up with