Browse Source

AP_Motors: replace header guard with pragma once

mission-4.1.18
Lucas De Marchi 9 years ago committed by Andrew Tridgell
parent
commit
7d9153feb8
  1. 6
      libraries/AP_Motors/AP_Motors.h
  2. 6
      libraries/AP_Motors/AP_MotorsCoax.h
  3. 6
      libraries/AP_Motors/AP_MotorsHeli.h
  4. 6
      libraries/AP_Motors/AP_MotorsHeli_RSC.h
  5. 6
      libraries/AP_Motors/AP_MotorsHeli_Single.h
  6. 6
      libraries/AP_Motors/AP_MotorsHexa.h
  7. 6
      libraries/AP_Motors/AP_MotorsMatrix.h
  8. 5
      libraries/AP_Motors/AP_MotorsMulticopter.h
  9. 6
      libraries/AP_Motors/AP_MotorsOcta.h
  10. 6
      libraries/AP_Motors/AP_MotorsOctaQuad.h
  11. 6
      libraries/AP_Motors/AP_MotorsQuad.h
  12. 6
      libraries/AP_Motors/AP_MotorsSingle.h
  13. 6
      libraries/AP_Motors/AP_MotorsTri.h
  14. 6
      libraries/AP_Motors/AP_MotorsY6.h
  15. 5
      libraries/AP_Motors/AP_Motors_Class.h

6
libraries/AP_Motors/AP_Motors.h

@ -1,7 +1,5 @@ @@ -1,7 +1,5 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_MOTORS_H__
#define __AP_MOTORS_H__
#pragma once
#include "AP_Motors_Class.h"
#include "AP_MotorsMulticopter.h"
@ -15,5 +13,3 @@ @@ -15,5 +13,3 @@
#include "AP_MotorsHeli_Single.h"
#include "AP_MotorsSingle.h"
#include "AP_MotorsCoax.h"
#endif // __AP_MOTORS_H__

6
libraries/AP_Motors/AP_MotorsCoax.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsCoax.h
/// @brief Motor and Servo control class for Co-axial helicopters with two motors and two flaps
#ifndef __AP_MOTORS_COAX_H__
#define __AP_MOTORS_COAX_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -71,5 +69,3 @@ protected: @@ -71,5 +69,3 @@ protected:
RC_Channel& _servo1;
RC_Channel& _servo2;
};
#endif // AP_MOTORSCOAX

6
libraries/AP_Motors/AP_MotorsHeli.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsHeli.h
/// @brief Motor control class for Traditional Heli
#ifndef __AP_MOTORS_HELI_H__
#define __AP_MOTORS_HELI_H__
#pragma once
#include <inttypes.h>
@ -246,5 +244,3 @@ protected: @@ -246,5 +244,3 @@ protected:
int16_t _collective_range = 0; // maximum absolute collective pitch range (500 - 1000)
uint8_t _servo_test_cycle_counter = 0; // number of test cycles left to run after bootup
};
#endif // AP_MOTORSHELI

6
libraries/AP_Motors/AP_MotorsHeli_RSC.h

@ -1,7 +1,5 @@ @@ -1,7 +1,5 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_MOTORS_HELI_RSC_H__
#define __AP_MOTORS_HELI_RSC_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -118,5 +116,3 @@ private: @@ -118,5 +116,3 @@ private:
// write_rsc - outputs pwm onto output rsc channel. servo_out parameter is of the range 0 ~ 1000
void write_rsc(int16_t servo_out);
};
#endif // AP_MOTORS_HELI_RSC_H

6
libraries/AP_Motors/AP_MotorsHeli_Single.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsHeli_Single.h
/// @brief Motor control class for traditional heli
#ifndef __AP_MOTORS_HELI_SINGLE_H__
#define __AP_MOTORS_HELI_SINGLE_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -186,5 +184,3 @@ protected: @@ -186,5 +184,3 @@ protected:
bool _acro_tail = false;
};
#endif // __AP_MOTORS_HELI_SINGLE_H__

6
libraries/AP_Motors/AP_MotorsHexa.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsHexa.h
/// @brief Motor control class for Hexacopters
#ifndef __AP_MOTORS_HEXA_H__
#define __AP_MOTORS_HEXA_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -26,5 +24,3 @@ public: @@ -26,5 +24,3 @@ public:
protected:
};
#endif // AP_MOTORSHEXA

6
libraries/AP_Motors/AP_MotorsMatrix.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsMatrix.h
/// @brief Motor control class for Matrixcopters
#ifndef __AP_MOTORS_MATRIX_H__
#define __AP_MOTORS_MATRIX_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -79,5 +77,3 @@ protected: @@ -79,5 +77,3 @@ protected:
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to yaw (normally 1 or -1)
uint8_t _test_order[AP_MOTORS_MAX_NUM_MOTORS]; // order of the motors in the test sequence
};
#endif // AP_MOTORSMATRIX

5
libraries/AP_Motors/AP_MotorsMulticopter.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsMulticopter.h
/// @brief Motor control class for Multicopters
#ifndef __AP_MOTORS_MULTICOPTER_H__
#define __AP_MOTORS_MULTICOPTER_H__
#pragma once
#include "AP_Motors_Class.h"
@ -177,4 +175,3 @@ protected: @@ -177,4 +175,3 @@ protected:
float _lift_max; // maximum lift ratio from battery voltage
float _throttle_limit; // ratio of throttle limit between hover and maximum
};
#endif // __AP_MOTORS_MULTICOPTER_H__

6
libraries/AP_Motors/AP_MotorsOcta.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsOcta.h
/// @brief Motor control class for Octacopters
#ifndef __AP_MOTORS_OCTA_H__
#define __AP_MOTORS_OCTA_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -26,5 +24,3 @@ public: @@ -26,5 +24,3 @@ public:
protected:
};
#endif // AP_MOTORSOCTA

6
libraries/AP_Motors/AP_MotorsOctaQuad.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsOctaQuad.h
/// @brief Motor control class for OctaQuadcopters
#ifndef __AP_MOTORS_OCTA_QUAD_H__
#define __AP_MOTORS_OCTA_QUAD_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -26,5 +24,3 @@ public: @@ -26,5 +24,3 @@ public:
protected:
};
#endif // AP_MOTORSOCTAQUAD

6
libraries/AP_Motors/AP_MotorsQuad.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsQuad.h
/// @brief Motor control class for Quadcopters
#ifndef __AP_MOTORS_QUAD_H__
#define __AP_MOTORS_QUAD_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -26,5 +24,3 @@ public: @@ -26,5 +24,3 @@ public:
protected:
};
#endif // AP_MOTORSQUAD

6
libraries/AP_Motors/AP_MotorsSingle.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsSingle.h
/// @brief Motor and Servo control class for Singlecopters
#ifndef __AP_MOTORS_SING_H__
#define __AP_MOTORS_SING_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -74,5 +72,3 @@ protected: @@ -74,5 +72,3 @@ protected:
RC_Channel& _servo3;
RC_Channel& _servo4;
};
#endif // AP_MOTORSSINGLE

6
libraries/AP_Motors/AP_MotorsTri.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsTri.h
/// @brief Motor control class for Tricopters
#ifndef __AP_MOTORS_TRI_H__
#define __AP_MOTORS_TRI_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -64,5 +62,3 @@ protected: @@ -64,5 +62,3 @@ protected:
AP_Int16 _yaw_servo_min; // Minimum angle limit of yaw servo
AP_Int16 _yaw_servo_max; // Maximum angle limit of yaw servo
};
#endif // AP_MOTORSTRI

6
libraries/AP_Motors/AP_MotorsY6.h

@ -2,9 +2,7 @@ @@ -2,9 +2,7 @@
/// @file AP_MotorsY6.h
/// @brief Motor control class for Y6 frames
#ifndef __AP_MOTORS_Y6_H__
#define __AP_MOTORS_Y6_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -28,5 +26,3 @@ public: @@ -28,5 +26,3 @@ public:
protected:
};
#endif // AP_MOTORSY6

5
libraries/AP_Motors/AP_Motors_Class.h

@ -1,7 +1,5 @@ @@ -1,7 +1,5 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_MOTORS_CLASS_H__
#define __AP_MOTORS_CLASS_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
@ -169,4 +167,3 @@ protected: @@ -169,4 +167,3 @@ protected:
uint8_t _motor_map[AP_MOTORS_MAX_NUM_MOTORS];
uint16_t _motor_map_mask;
};
#endif // __AP_MOTORS_CLASS_H__

Loading…
Cancel
Save