From 8f6bed23cfcbec3e712d2a49993bcf5f5fdd1eb4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 18 Aug 2021 21:42:16 +1000 Subject: [PATCH] AP_AccelCal: move from HAL_NO_GCS to HAL_GCS_ENABLED --- libraries/AP_AccelCal/AP_AccelCal.cpp | 2 ++ libraries/AP_AccelCal/AP_AccelCal.h | 6 ++++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/AP_AccelCal/AP_AccelCal.cpp b/libraries/AP_AccelCal/AP_AccelCal.cpp index 8fbf9b09c1..dd0c0d9b1f 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.cpp +++ b/libraries/AP_AccelCal/AP_AccelCal.cpp @@ -361,6 +361,7 @@ bool AP_AccelCal::client_active(uint8_t client_num) return (bool)_clients[client_num]->_acal_get_calibrator(0); } +#if HAL_GCS_ENABLED void AP_AccelCal::handleMessage(const mavlink_message_t &msg) { if (!_waiting_for_mavlink_ack) { @@ -383,6 +384,7 @@ bool AP_AccelCal::gcs_vehicle_position(float position) return false; } +#endif // true if we are in a calibration process bool AP_AccelCal::running(void) const diff --git a/libraries/AP_AccelCal/AP_AccelCal.h b/libraries/AP_AccelCal/AP_AccelCal.h index 1eb6e43357..f8c4badda2 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.h +++ b/libraries/AP_AccelCal/AP_AccelCal.h @@ -1,11 +1,11 @@ #pragma once -#include +#include #include "AccelCalibrator.h" #include "AP_Vehicle/AP_Vehicle_Type.h" #ifndef HAL_INS_ACCELCAL_ENABLED -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED #define HAL_INS_ACCELCAL_ENABLED 1 #else #define HAL_INS_ACCELCAL_ENABLED 0 @@ -42,7 +42,9 @@ public: // interface to the clients for registration static void register_client(AP_AccelCal_Client* client); +#if HAL_GCS_ENABLED void handleMessage(const mavlink_message_t &msg); +#endif // true if we are in a calibration process bool running(void) const;