mirror of https://github.com/ArduPilot/ardupilot
AP_AccelCal: do not add accelcal if no GCS iface available
This commit is contained in:
parent
c4caf2ff54
commit
0d393a3cf7
|
@ -17,6 +17,7 @@
|
|||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#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
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue