AP_NavEKF: replace header guard with pragma once
This commit is contained in:
parent
e40b87cd0e
commit
bb0d96cedd
@ -17,9 +17,7 @@
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef AP_NavEKF
|
||||
#define AP_NavEKF
|
||||
#pragma once
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
@ -300,5 +298,3 @@ private:
|
||||
AP_Int8 _gpsCheck; // Bitmask controlling which preflight GPS checks are bypassed
|
||||
|
||||
};
|
||||
|
||||
#endif // AP_NavEKF
|
||||
|
@ -17,9 +17,7 @@
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef AP_NavEKF_core
|
||||
#define AP_NavEKF_core
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_NavEKF/AP_NavEKF.h>
|
||||
@ -875,5 +873,3 @@ private:
|
||||
// vehicle specific initial gyro bias uncertainty
|
||||
float InitialGyroBiasUncertainty(void) const;
|
||||
};
|
||||
|
||||
#endif // AP_NavEKF_core
|
||||
|
@ -15,9 +15,7 @@
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef AP_Nav_Common
|
||||
#define AP_Nav_Common
|
||||
#pragma once
|
||||
|
||||
union nav_filter_status {
|
||||
struct {
|
||||
@ -55,5 +53,3 @@ union nav_gps_status {
|
||||
} flags;
|
||||
uint16_t value;
|
||||
};
|
||||
|
||||
#endif // AP_Nav_Common
|
||||
|
Loading…
Reference in New Issue
Block a user