diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h
index ab8a589503..1e0a5048ea 100644
--- a/libraries/AP_GPS/AP_GPS.h
+++ b/libraries/AP_GPS/AP_GPS.h
@@ -13,9 +13,7 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see .
*/
-
-#ifndef __AP_GPS_H__
-#define __AP_GPS_H__
+#pragma once
#include
#include
@@ -411,5 +409,3 @@ private:
#include "AP_GPS_SBF.h"
#include "AP_GPS_GSOF.h"
#include "AP_GPS_ERB.h"
-
-#endif // __AP_GPS_H__
diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h
index 448aac363c..61a049675f 100644
--- a/libraries/AP_GPS/AP_GPS_GSOF.h
+++ b/libraries/AP_GPS/AP_GPS_GSOF.h
@@ -18,9 +18,7 @@
// Trimble GPS driver for ArduPilot.
// Code by Michael Oborne
//
-
-#ifndef __AP_GPS_GSOF_H__
-#define __AP_GPS_GSOF_H__
+#pragma once
#include "AP_GPS.h"
@@ -88,5 +86,3 @@ private:
uint32_t crc_error_counter = 0;
uint32_t last_injected_data_ms = 0;
};
-
-#endif // __AP_GPS_GSOF_H__
diff --git a/libraries/AP_GPS/AP_GPS_MTK.h b/libraries/AP_GPS/AP_GPS_MTK.h
index 255ab58bae..230880e4be 100644
--- a/libraries/AP_GPS/AP_GPS_MTK.h
+++ b/libraries/AP_GPS/AP_GPS_MTK.h
@@ -22,8 +22,7 @@
//
// Note - see AP_GPS_MTK16.h for firmware 1.6 and later.
//
-#ifndef __AP_GPS_MTK_H__
-#define __AP_GPS_MTK_H__
+#pragma once
#include "AP_GPS.h"
#include "AP_GPS_MTK_Common.h"
@@ -80,5 +79,3 @@ private:
static const char _initialisation_blob[];
};
-
-#endif // __AP_GPS_MTK_H__
diff --git a/libraries/AP_GPS/AP_GPS_MTK19.h b/libraries/AP_GPS/AP_GPS_MTK19.h
index 210b9d5d96..1197b5745c 100644
--- a/libraries/AP_GPS/AP_GPS_MTK19.h
+++ b/libraries/AP_GPS/AP_GPS_MTK19.h
@@ -20,8 +20,7 @@
//
// GPS configuration : Custom protocol per "Customize Function Specification, 3D Robotics, v1.6, v1.7, v1.8, v1.9"
//
-#ifndef AP_GPS_MTK19_h
-#define AP_GPS_MTK19_h
+#pragma once
#include "AP_GPS.h"
#include "AP_GPS_MTK_Common.h"
@@ -81,5 +80,3 @@ private:
uint8_t bytes[];
} _buffer;
};
-
-#endif // AP_GPS_MTK19_H
diff --git a/libraries/AP_GPS/AP_GPS_MTK_Common.h b/libraries/AP_GPS/AP_GPS_MTK_Common.h
index 39675cc64f..6b8718f044 100644
--- a/libraries/AP_GPS/AP_GPS_MTK_Common.h
+++ b/libraries/AP_GPS/AP_GPS_MTK_Common.h
@@ -19,9 +19,7 @@
// Code by Michael Smith, Jordi Munoz and Jose Julio, Craig Elder, DIYDrones.com
//
// Common definitions for MediaTek GPS modules.
-
-#ifndef __AP_GPS_MTK_COMMON_H__
-#define __AP_GPS_MTK_COMMON_H__
+#pragma once
#define MTK_SET_BINARY "$PGCMD,16,0,0,0,0,0*6A\r\n"
#define MTK_SET_NMEA "$PGCMD,16,1,1,1,1,1*6B\r\n"
@@ -41,5 +39,3 @@
#define WAAS_ON "$PMTK301,2*2E\r\n"
#define WAAS_OFF "$PMTK301,0*2C\r\n"
-
-#endif // __AP_GPS_MTK_COMMON_H__
diff --git a/libraries/AP_GPS/AP_GPS_NMEA.h b/libraries/AP_GPS/AP_GPS_NMEA.h
index 7471a12286..8a3da74bea 100644
--- a/libraries/AP_GPS/AP_GPS_NMEA.h
+++ b/libraries/AP_GPS/AP_GPS_NMEA.h
@@ -42,10 +42,7 @@
/// qualifier field (this is common with e.g. older SiRF units) it is
/// not considered a source of fix-valid information.
///
-
-
-#ifndef __AP_GPS_NMEA_H__
-#define __AP_GPS_NMEA_H__
+#pragma once
#include "AP_GPS.h"
@@ -162,5 +159,3 @@ private:
static const char _initialisation_blob[];
};
-
-#endif // __AP_GPS_NMEA_H__
diff --git a/libraries/AP_GPS/AP_GPS_PX4.h b/libraries/AP_GPS/AP_GPS_PX4.h
index e59e7cb290..a7fcb961b0 100644
--- a/libraries/AP_GPS/AP_GPS_PX4.h
+++ b/libraries/AP_GPS/AP_GPS_PX4.h
@@ -18,8 +18,7 @@
// GPS proxy driver for APM on PX4 platforms
// Code by Holger Steinhaus
//
-#ifndef __AP_GPS_PX4_H__
-#define __AP_GPS_PX4_H__
+#pragma once
#include
#include "AP_GPS.h"
@@ -37,5 +36,3 @@ private:
struct vehicle_gps_position_s _gps_pos;
};
#endif // CONFIG_HAL_BOARD
-#endif // AP_GPS_PX4_H
-
diff --git a/libraries/AP_GPS/AP_GPS_SBF.h b/libraries/AP_GPS/AP_GPS_SBF.h
index 368b6601ed..ef4c448a4c 100644
--- a/libraries/AP_GPS/AP_GPS_SBF.h
+++ b/libraries/AP_GPS/AP_GPS_SBF.h
@@ -18,9 +18,7 @@
// Septentrio GPS driver for ArduPilot.
// Code by Michael Oborne
//
-
-#ifndef __AP_GPS_SBF_H__
-#define __AP_GPS_SBF_H__
+#pragma once
#include "AP_GPS.h"
@@ -138,6 +136,3 @@ private:
void log_ExtEventPVTGeodetic(const msg4007 &temp);
};
-
-#endif // __AP_GPS_SBF_H__
-
diff --git a/libraries/AP_GPS/AP_GPS_SBP.h b/libraries/AP_GPS/AP_GPS_SBP.h
index 4c82f6b541..308ad61fb9 100644
--- a/libraries/AP_GPS/AP_GPS_SBP.h
+++ b/libraries/AP_GPS/AP_GPS_SBP.h
@@ -20,9 +20,7 @@
//
// Swift Binary Protocol format: http://docs.swift-nav.com/
//
-
-#ifndef __AP_GPS_SBP_H__
-#define __AP_GPS_SBP_H__
+#pragma once
#include "AP_GPS.h"
@@ -169,5 +167,3 @@ private:
};
-
-#endif // __AP_GPS_SBP_H__
diff --git a/libraries/AP_GPS/AP_GPS_SIRF.h b/libraries/AP_GPS/AP_GPS_SIRF.h
index 7ee9f0aa60..21e4179b79 100644
--- a/libraries/AP_GPS/AP_GPS_SIRF.h
+++ b/libraries/AP_GPS/AP_GPS_SIRF.h
@@ -18,8 +18,7 @@
// SiRF Binary GPS driver for ArduPilot and ArduPilotMega.
// Code by Michael Smith.
//
-#ifndef __AP_GPS_SIRF_H__
-#define __AP_GPS_SIRF_H__
+#pragma once
#include
#include
@@ -105,5 +104,3 @@ private:
static const uint8_t _initialisation_blob[];
};
-
-#endif // AP_GPS_SIRF_h
diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h
index 50910f3669..5ebd5685ec 100644
--- a/libraries/AP_GPS/AP_GPS_UBLOX.h
+++ b/libraries/AP_GPS/AP_GPS_UBLOX.h
@@ -19,9 +19,7 @@
// Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
//
// UBlox Lea6H protocol: http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
-
-#ifndef __AP_GPS_UBLOX_H__
-#define __AP_GPS_UBLOX_H__
+#pragma once
#include
#include "AP_GPS.h"
@@ -537,5 +535,3 @@ private:
return (uint8_t)(ubx_msg + (state.instance * UBX_MSG_TYPES));
}
};
-
-#endif // __AP_GPS_UBLOX_H__
diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h
index 8543b70f8b..a6e019afc6 100644
--- a/libraries/AP_GPS/GPS_Backend.h
+++ b/libraries/AP_GPS/GPS_Backend.h
@@ -17,8 +17,7 @@
/*
GPS driver backend class
*/
-#ifndef __AP_GPS_BACKEND_H__
-#define __AP_GPS_BACKEND_H__
+#pragma once
#include
#include "AP_GPS.h"
@@ -70,5 +69,3 @@ protected:
*/
void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds);
};
-
-#endif // __AP_GPS_BACKEND_H__