Browse Source

AP_GPS: create and use AP_GPS_BACKEND_DEFAULT_ENABLED

Allows for all backends to be set to off by default.
gps-1.3.1
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
60b8277e1b
  1. 2
      libraries/AP_GPS/AP_GPS_ERB.h
  2. 2
      libraries/AP_GPS/AP_GPS_GSOF.h
  3. 2
      libraries/AP_GPS/AP_GPS_MAV.h
  4. 2
      libraries/AP_GPS/AP_GPS_NMEA.h
  5. 2
      libraries/AP_GPS/AP_GPS_NOVA.h
  6. 2
      libraries/AP_GPS/AP_GPS_SBF.h
  7. 2
      libraries/AP_GPS/AP_GPS_SBP.h
  8. 2
      libraries/AP_GPS/AP_GPS_SBP2.h
  9. 2
      libraries/AP_GPS/AP_GPS_SIRF.h
  10. 4
      libraries/AP_GPS/GPS_Backend.h

2
libraries/AP_GPS/AP_GPS_ERB.h

@ -25,7 +25,7 @@ @@ -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

2
libraries/AP_GPS/AP_GPS_GSOF.h

@ -23,7 +23,7 @@ @@ -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

2
libraries/AP_GPS/AP_GPS_MAV.h

@ -26,7 +26,7 @@ @@ -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

2
libraries/AP_GPS/AP_GPS_NMEA.h

@ -47,7 +47,7 @@ @@ -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

2
libraries/AP_GPS/AP_GPS_NOVA.h

@ -23,7 +23,7 @@ @@ -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

2
libraries/AP_GPS/AP_GPS_SBF.h

@ -23,7 +23,7 @@ @@ -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

2
libraries/AP_GPS/AP_GPS_SBP.h

@ -25,7 +25,7 @@ @@ -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

2
libraries/AP_GPS/AP_GPS_SBP2.h

@ -25,7 +25,7 @@ @@ -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

2
libraries/AP_GPS/AP_GPS_SIRF.h

@ -26,7 +26,7 @@ @@ -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

4
libraries/AP_GPS/GPS_Backend.h

@ -22,6 +22,10 @@ @@ -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…
Cancel
Save