mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: reorganize includes
Due to the way the headers are organized a single change in a AP_GPS backend would trigger a rebuild for most of the files in the project. Time could be saved by using ccache (since most of the things didn't change) but we can do better, i.e. re-organize the headers so we don't have to re-build everything. This makes internal headers internal and then other libraries only depend on the AP_GPS.h header.
This commit is contained in:
parent
e83a3d8185
commit
ff10d1136c
@ -21,6 +21,19 @@
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#include "AP_GPS_ERB.h"
|
||||
#include "AP_GPS_GSOF.h"
|
||||
#include "AP_GPS_MTK.h"
|
||||
#include "AP_GPS_MTK19.h"
|
||||
#include "AP_GPS_NMEA.h"
|
||||
#include "AP_GPS_PX4.h"
|
||||
#include "AP_GPS_QURT.h"
|
||||
#include "AP_GPS_SBF.h"
|
||||
#include "AP_GPS_SBP.h"
|
||||
#include "AP_GPS_SIRF.h"
|
||||
#include "AP_GPS_UBLOX.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
// table of user settable parameters
|
||||
|
@ -397,16 +397,3 @@ private:
|
||||
};
|
||||
|
||||
#define GPS_BAUD_TIME_MS 1200
|
||||
|
||||
#include "GPS_Backend.h"
|
||||
#include "AP_GPS_UBLOX.h"
|
||||
#include "AP_GPS_MTK.h"
|
||||
#include "AP_GPS_MTK19.h"
|
||||
#include "AP_GPS_NMEA.h"
|
||||
#include "AP_GPS_SIRF.h"
|
||||
#include "AP_GPS_SBP.h"
|
||||
#include "AP_GPS_PX4.h"
|
||||
#include "AP_GPS_QURT.h"
|
||||
#include "AP_GPS_SBF.h"
|
||||
#include "AP_GPS_GSOF.h"
|
||||
#include "AP_GPS_ERB.h"
|
||||
|
@ -21,7 +21,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
class AP_GPS_ERB : public AP_GPS_Backend
|
||||
{
|
||||
|
@ -21,6 +21,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
class AP_GPS_GSOF : public AP_GPS_Backend
|
||||
{
|
||||
|
@ -25,6 +25,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
#include "AP_GPS_MTK_Common.h"
|
||||
|
||||
class AP_GPS_MTK : public AP_GPS_Backend {
|
||||
|
@ -23,6 +23,7 @@
|
||||
// Note that this driver supports both the 1.6 and 1.9 protocol varients
|
||||
//
|
||||
|
||||
#include "AP_GPS_MTK.h"
|
||||
#include "AP_GPS_MTK19.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
@ -23,6 +23,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
#include "AP_GPS_MTK_Common.h"
|
||||
|
||||
#define MTK_GPS_REVISION_V16 16
|
||||
|
@ -45,6 +45,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
/// NMEA parser
|
||||
///
|
||||
|
@ -21,7 +21,10 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include <modules/uORB/topics/vehicle_gps_position.h>
|
||||
|
||||
|
@ -17,7 +17,10 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_QURT
|
||||
|
||||
class AP_GPS_QURT : public AP_GPS_Backend {
|
||||
|
@ -21,6 +21,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#define SBF_SETUP_MSG "\nsso, Stream1, COM1, PVTGeodetic+DOP+ExtEventPVTGeodetic, msec100\n"
|
||||
|
||||
|
@ -23,6 +23,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
class AP_GPS_SBP : public AP_GPS_Backend
|
||||
{
|
||||
|
@ -20,9 +20,11 @@
|
||||
//
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C\r\n"
|
||||
|
||||
|
@ -22,7 +22,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
/*
|
||||
* try to put a UBlox into binary mode. This is in two parts.
|
||||
|
@ -15,6 +15,7 @@
|
||||
*/
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -73,4 +73,4 @@ struct SBP_detect_state {
|
||||
uint8_t msg_len;
|
||||
uint16_t crc_so_far;
|
||||
uint16_t crc;
|
||||
};
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user