AP_AccelCal: move from HAL_NO_GCS to HAL_GCS_ENABLED

This commit is contained in:
Peter Barker 2021-08-18 21:42:16 +10:00 committed by Peter Barker
parent b43c9961a3
commit 8f6bed23cf
2 changed files with 6 additions and 2 deletions

View File

@ -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

View File

@ -1,11 +1,11 @@
#pragma once
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS.h>
#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;