diff --git a/libraries/AP_AccelCal/AP_AccelCal.cpp b/libraries/AP_AccelCal/AP_AccelCal.cpp index 0867cfbf92..8cf1fc126a 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.cpp +++ b/libraries/AP_AccelCal/AP_AccelCal.cpp @@ -12,12 +12,13 @@ */ #include "AP_AccelCal.h" -#include -#include -#include -#include #if HAL_INS_ACCELCAL_ENABLED + +#include +#include +#include + #define AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS 1000 #define _printf(fmt, args ...) do { \ diff --git a/libraries/AP_AccelCal/AP_AccelCal.h b/libraries/AP_AccelCal/AP_AccelCal.h index 5b0e26d082..af899a6e44 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.h +++ b/libraries/AP_AccelCal/AP_AccelCal.h @@ -1,8 +1,7 @@ #pragma once -#include -#include "AccelCalibrator.h" -#include "AP_Vehicle/AP_Vehicle_Type.h" +#include +#include #ifndef HAL_INS_ACCELCAL_ENABLED #if HAL_GCS_ENABLED @@ -12,6 +11,10 @@ #endif #endif +#include +#include "AccelCalibrator.h" +#include "AP_Vehicle/AP_Vehicle_Type.h" + #define AP_ACCELCAL_MAX_NUM_CLIENTS 4 class GCS_MAVLINK; class AP_AccelCal_Client; @@ -50,7 +53,7 @@ public: bool running(void) const; private: - GCS_MAVLINK *_gcs; + class GCS_MAVLINK *_gcs; bool _use_gcs_snoop; bool _waiting_for_mavlink_ack = false; uint32_t _last_position_request_ms;