mirror of https://github.com/ArduPilot/ardupilot
AP_AccelCal: include GCS_Config.h rather than GCS.h
This commit is contained in:
parent
3b3497eba0
commit
b7ce25c23b
|
@ -12,12 +12,13 @@
|
|||
*/
|
||||
|
||||
#include "AP_AccelCal.h"
|
||||
#include <stdarg.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_INS_ACCELCAL_ENABLED
|
||||
|
||||
#include <stdarg.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#define AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS 1000
|
||||
|
||||
#define _printf(fmt, args ...) do { \
|
||||
|
|
|
@ -1,8 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include "AccelCalibrator.h"
|
||||
#include "AP_Vehicle/AP_Vehicle_Type.h"
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#include <GCS_MAVLink/GCS_config.h>
|
||||
|
||||
#ifndef HAL_INS_ACCELCAL_ENABLED
|
||||
#if HAL_GCS_ENABLED
|
||||
|
@ -12,6 +11,10 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#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;
|
||||
|
|
Loading…
Reference in New Issue