mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_GPS: use AP_GPS_ENABLED to exclude more code when GPS not compiled in
This commit is contained in:
parent
9a054876ff
commit
0824eca776
@ -12,6 +12,10 @@
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "AP_GPS_config.h"
|
||||
|
||||
#if AP_GPS_ENABLED
|
||||
|
||||
#include "AP_GPS.h"
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
@ -2330,3 +2334,5 @@ AP_GPS &gps()
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // AP_GPS_ENABLED
|
||||
|
@ -14,6 +14,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_GPS_config.h"
|
||||
|
||||
#if AP_GPS_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <inttypes.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
@ -59,10 +63,6 @@
|
||||
#define GPS_MOVING_BASELINE GPS_MAX_RECEIVERS>1
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MSP_GPS_ENABLED
|
||||
#define HAL_MSP_GPS_ENABLED HAL_MSP_SENSORS_ENABLED
|
||||
#endif
|
||||
|
||||
#if GPS_MOVING_BASELINE
|
||||
#include "MovingBase.h"
|
||||
#endif // GPS_MOVING_BASELINE
|
||||
@ -791,3 +791,5 @@ private:
|
||||
namespace AP {
|
||||
AP_GPS &gps();
|
||||
};
|
||||
|
||||
#endif // AP_GPS_ENABLED
|
||||
|
@ -20,11 +20,13 @@
|
||||
// UBlox Lea6H protocol: http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
|
||||
#pragma once
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
#include "AP_GPS_config.h"
|
||||
|
||||
#if AP_GPS_UBLOX_ENABLED
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
/*
|
||||
|
@ -12,7 +12,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_DRONECAN_ENABLED
|
||||
#define AP_GPS_DRONECAN_ENABLED HAL_ENABLE_DRONECAN_DRIVERS
|
||||
#define AP_GPS_DRONECAN_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_ERB_ENABLED
|
||||
@ -27,6 +27,10 @@
|
||||
#define AP_GPS_MAV_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MSP_GPS_ENABLED
|
||||
#define HAL_MSP_GPS_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_MSP_SENSORS_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_NMEA_ENABLED
|
||||
#define AP_GPS_NMEA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
@ -56,5 +60,5 @@
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_UBLOX_ENABLED
|
||||
#define AP_GPS_UBLOX_ENABLED 1
|
||||
#define AP_GPS_UBLOX_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
@ -13,6 +13,10 @@
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_GPS_config.h"
|
||||
|
||||
#if AP_GPS_ENABLED
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
@ -524,3 +528,5 @@ void AP_GPS_Backend::logging_start(void)
|
||||
logging_loop();
|
||||
}
|
||||
#endif // AP_GPS_DEBUG_LOGGING_ENABLED
|
||||
|
||||
#endif // AP_GPS_ENABLED
|
||||
|
@ -18,6 +18,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_GPS_config.h"
|
||||
|
||||
#if AP_GPS_ENABLED
|
||||
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <GCS_MAVLink/GCS_config.h>
|
||||
#include <AP_RTC/JitterCorrection.h>
|
||||
@ -180,3 +184,5 @@ private:
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
#endif // AP_GPS_ENABLED
|
||||
|
@ -218,6 +218,7 @@ define AP_AIRSPEED_ASP5033_ENABLED 1
|
||||
define AP_GPS_BACKEND_DEFAULT_ENABLED 0
|
||||
define AP_GPS_UBLOX_ENABLED 1
|
||||
define AP_GPS_NMEA_ENABLED 1
|
||||
define HAL_MSP_GPS_ENABLED 1
|
||||
|
||||
define AP_TRAMP_ENABLED 1
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user