AP_GPS: make AP_GPS_MAV dependent on HAL_GCS_ENABLED
This commit is contained in:
parent
6ee9f01ffb
commit
e6ac368972
@ -16,11 +16,14 @@
|
||||
//
|
||||
// MAVLINK GPS driver
|
||||
//
|
||||
#include "AP_GPS_MAV.h"
|
||||
#include <stdint.h>
|
||||
|
||||
#include "AP_GPS_config.h"
|
||||
|
||||
#if AP_GPS_MAV_ENABLED
|
||||
|
||||
#include "AP_GPS_MAV.h"
|
||||
#include <stdint.h>
|
||||
|
||||
// Reading does nothing in this class; we simply return whether or not
|
||||
// the latest reading has been consumed. By calling this function we assume
|
||||
// the caller is consuming the new data;
|
||||
|
@ -19,16 +19,15 @@
|
||||
//
|
||||
#pragma once
|
||||
|
||||
#include "AP_GPS_config.h"
|
||||
|
||||
#if AP_GPS_MAV_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_MAV_ENABLED
|
||||
#define AP_GPS_MAV_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_MAV_ENABLED
|
||||
class AP_GPS_MAV : public AP_GPS_Backend {
|
||||
public:
|
||||
|
||||
@ -47,4 +46,5 @@ private:
|
||||
uint32_t first_week;
|
||||
JitterCorrection jitter{2000};
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif // AP_GPS_MAV_ENABLED
|
||||
|
@ -1,6 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#include <GCS_MAVLink/GCS_config.h>
|
||||
|
||||
#ifndef AP_GPS_ENABLED
|
||||
#define AP_GPS_ENABLED 1
|
||||
@ -22,6 +23,10 @@
|
||||
#define AP_GPS_GSOF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_MAV_ENABLED
|
||||
#define AP_GPS_MAV_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_NMEA_ENABLED
|
||||
#define AP_GPS_NMEA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user