diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 11212286fb..3a74414444 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -45,7 +45,7 @@ extern const AP_HAL::HAL& hal; -#if APM_BUILD_COPTER_OR_HELI() +#if APM_BUILD_COPTER_OR_HELI #define DEFAULT_GYRO_FILTER 20 #define DEFAULT_ACCEL_FILTER 20 #define DEFAULT_STILL_THRESH 2.5f