diff --git a/libraries/AP_RPM/AP_RPM.h b/libraries/AP_RPM/AP_RPM.h
index 9cf86dde23..4f7fb6babd 100644
--- a/libraries/AP_RPM/AP_RPM.h
+++ b/libraries/AP_RPM/AP_RPM.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 __RPM_H__
-#define __RPM_H__
+#pragma once
#include
#include
@@ -97,4 +95,3 @@ private:
void detect_instance(uint8_t instance);
void update_instance(uint8_t instance);
};
-#endif // __RPM_H__
diff --git a/libraries/AP_RPM/RPM_Backend.h b/libraries/AP_RPM/RPM_Backend.h
index 61138e6c03..6cea9fba19 100644
--- a/libraries/AP_RPM/RPM_Backend.h
+++ b/libraries/AP_RPM/RPM_Backend.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_RPM_BACKEND_H__
-#define __AP_RPM_BACKEND_H__
+#pragma once
#include
#include
@@ -39,4 +37,3 @@ protected:
AP_RPM &ap_rpm;
AP_RPM::RPM_State &state;
};
-#endif // __AP_RPM_BACKEND_H__
diff --git a/libraries/AP_RPM/RPM_PX4_PWM.h b/libraries/AP_RPM/RPM_PX4_PWM.h
index 9b5350a682..c4c1ea6824 100644
--- a/libraries/AP_RPM/RPM_PX4_PWM.h
+++ b/libraries/AP_RPM/RPM_PX4_PWM.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_RPM_PX4_PWM_H
-#define AP_RPM_PX4_PWM_H
+#pragma once
#include "AP_RPM.h"
#include "RPM_Backend.h"
@@ -41,5 +39,3 @@ private:
ModeFilterFloat_Size5 signal_quality_filter {3};
};
-
-#endif // AP_RPM_PX4_PWM_H
diff --git a/libraries/AP_RPM/RPM_SITL.h b/libraries/AP_RPM/RPM_SITL.h
index 2688dfebf8..4a94be62b1 100644
--- a/libraries/AP_RPM/RPM_SITL.h
+++ b/libraries/AP_RPM/RPM_SITL.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_RPM_SITL_H
-#define AP_RPM_SITL_H
+#pragma once
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
@@ -37,4 +35,3 @@ private:
};
#endif // CONFIG_HAL_BOARD
-#endif // AP_RPM_SITL_H