mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: create and use AP_GPS_BACKEND_DEFAULT_ENABLED
Allows for all backends to be set to off by default.
This commit is contained in:
parent
bcc60d0945
commit
60b8277e1b
@ -25,7 +25,7 @@
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_ERB_ENABLED
|
||||
#define AP_GPS_ERB_ENABLED 1
|
||||
#define AP_GPS_ERB_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_ERB_ENABLED
|
||||
|
@ -23,7 +23,7 @@
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_GSOF_ENABLED
|
||||
#define AP_GPS_GSOF_ENABLED 1
|
||||
#define AP_GPS_GSOF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_GSOF_ENABLED
|
||||
|
@ -26,7 +26,7 @@
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_MAV_ENABLED
|
||||
#define AP_GPS_MAV_ENABLED 1
|
||||
#define AP_GPS_MAV_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_MAV_ENABLED
|
||||
|
@ -47,7 +47,7 @@
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_NMEA_ENABLED
|
||||
#define AP_GPS_NMEA_ENABLED 1
|
||||
#define AP_GPS_NMEA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_NMEA_ENABLED
|
||||
|
@ -23,7 +23,7 @@
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_NOVA_ENABLED
|
||||
#define AP_GPS_NOVA_ENABLED 1
|
||||
#define AP_GPS_NOVA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_NOVA_ENABLED
|
||||
|
@ -23,7 +23,7 @@
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_SBF_ENABLED
|
||||
#define AP_GPS_SBF_ENABLED 1
|
||||
#define AP_GPS_SBF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_SBF_ENABLED
|
||||
|
@ -25,7 +25,7 @@
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_SBP_ENABLED
|
||||
#define AP_GPS_SBP_ENABLED 1
|
||||
#define AP_GPS_SBP_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_SBP_ENABLED
|
||||
|
@ -25,7 +25,7 @@
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_SBP2_ENABLED
|
||||
#define AP_GPS_SBP2_ENABLED 1
|
||||
#define AP_GPS_SBP2_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_SBP2_ENABLED
|
||||
|
@ -26,7 +26,7 @@
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_SIRF_ENABLED
|
||||
#define AP_GPS_SIRF_ENABLED 1
|
||||
#define AP_GPS_SIRF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_SIRF_ENABLED
|
||||
|
@ -22,6 +22,10 @@
|
||||
#include <AP_RTC/JitterCorrection.h>
|
||||
#include "AP_GPS.h"
|
||||
|
||||
#ifndef AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#define AP_GPS_BACKEND_DEFAULT_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_DEBUG_LOGGING_ENABLED
|
||||
// enable this to log all bytes from the GPS. Also needs a call to
|
||||
// log_data() in each backend
|
||||
|
Loading…
Reference in New Issue
Block a user