Browse Source

AP_Compass: replace header guard with pragma once

mission-4.1.18
Lucas De Marchi 9 years ago
parent
commit
1a71c169fe
  1. 4
      libraries/AP_Compass/AP_Compass_AK8963.h
  2. 5
      libraries/AP_Compass/AP_Compass_Backend.h
  3. 5
      libraries/AP_Compass/AP_Compass_HIL.h
  4. 5
      libraries/AP_Compass/AP_Compass_HMC5843.h
  5. 7
      libraries/AP_Compass/AP_Compass_PX4.h
  6. 4
      libraries/AP_Compass/Compass.h

4
libraries/AP_Compass/AP_Compass_AK8963.h

@ -1,6 +1,5 @@ @@ -1,6 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef AP_Compass_AK8963_H
#define AP_Compass_AK8963_H
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
@ -122,4 +121,3 @@ private: @@ -122,4 +121,3 @@ private:
AP_HAL::I2CDriver *_i2c;
uint8_t _addr;
};
#endif

5
libraries/AP_Compass/AP_Compass_Backend.h

@ -18,8 +18,7 @@ @@ -18,8 +18,7 @@
Compass driver backend class. Each supported compass sensor type
needs to have an object derived from this class.
*/
#ifndef __AP_COMPASS_BACKEND_H__
#define __AP_COMPASS_BACKEND_H__
#pragma once
#include "Compass.h"
@ -81,5 +80,3 @@ protected: @@ -81,5 +80,3 @@ protected:
private:
void apply_corrections(Vector3f &mag, uint8_t i);
};
#endif // __AP_COMPASS_BACKEND_H__

5
libraries/AP_Compass/AP_Compass_HIL.h

@ -1,6 +1,5 @@ @@ -1,6 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef AP_Compass_HIL_H
#define AP_Compass_HIL_H
#pragma once
#include "Compass.h"
@ -19,5 +18,3 @@ public: @@ -19,5 +18,3 @@ public:
private:
uint8_t _compass_instance[HIL_NUM_COMPASSES];
};
#endif

5
libraries/AP_Compass/AP_Compass_HMC5843.h

@ -1,6 +1,5 @@ @@ -1,6 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef AP_Compass_HMC5843_H
#define AP_Compass_HMC5843_H
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
@ -120,5 +119,3 @@ private: @@ -120,5 +119,3 @@ private:
AuxiliaryBusSlave *_slave = nullptr;
bool _started = false;
};
#endif

7
libraries/AP_Compass/AP_Compass_PX4.h

@ -1,7 +1,5 @@ @@ -1,7 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef AP_Compass_PX4_H
#define AP_Compass_PX4_H
#pragma once
#include "Compass.h"
#include "AP_Compass_Backend.h"
@ -26,6 +24,3 @@ private: @@ -26,6 +24,3 @@ private:
uint32_t _count[COMPASS_MAX_INSTANCES];
uint64_t _last_timestamp[COMPASS_MAX_INSTANCES];
};
#endif // AP_Compass_PX4_H

4
libraries/AP_Compass/Compass.h

@ -1,6 +1,5 @@ @@ -1,6 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef Compass_h
#define Compass_h
#pragma once
#include <inttypes.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
@ -417,4 +416,3 @@ private: @@ -417,4 +416,3 @@ private:
#include "AP_Compass_LSM303D.h"
#include "AP_Compass_qflight.h"
#include "AP_Compass_QURT.h"
#endif

Loading…
Cancel
Save