diff --git a/libraries/AP_AccelCal/AP_AccelCal.cpp b/libraries/AP_AccelCal/AP_AccelCal.cpp index 45cd9b765e..8fbf9b09c1 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.cpp +++ b/libraries/AP_AccelCal/AP_AccelCal.cpp @@ -17,6 +17,7 @@ #include #include +#if HAL_INS_ACCELCAL_ENABLED #define AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS 1000 #define _printf(fmt, args ...) do { \ @@ -388,3 +389,4 @@ bool AP_AccelCal::running(void) const { return _status == ACCEL_CAL_WAITING_FOR_ORIENTATION || _status == ACCEL_CAL_COLLECTING_SAMPLE; } +#endif //HAL_INS_ACCELCAL_ENABLED diff --git a/libraries/AP_AccelCal/AP_AccelCal.h b/libraries/AP_AccelCal/AP_AccelCal.h index 5c1191fec1..1eb6e43357 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.h +++ b/libraries/AP_AccelCal/AP_AccelCal.h @@ -4,6 +4,14 @@ #include "AccelCalibrator.h" #include "AP_Vehicle/AP_Vehicle_Type.h" +#ifndef HAL_INS_ACCELCAL_ENABLED +#ifndef HAL_NO_GCS +#define HAL_INS_ACCELCAL_ENABLED 1 +#else +#define HAL_INS_ACCELCAL_ENABLED 0 +#endif +#endif + #define AP_ACCELCAL_MAX_NUM_CLIENTS 4 class GCS_MAVLINK; class AP_AccelCal_Client;