Skip to content

Commit

Permalink
AP_Motors: replace header guard with pragma once
Browse files Browse the repository at this point in the history
  • Loading branch information
lucasdemarchi authored and tridge committed Mar 16, 2016
1 parent d82e80c commit 7d9153f
Show file tree
Hide file tree
Showing 15 changed files with 15 additions and 73 deletions.
6 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_Motors.h
Original file line number Diff line number Diff line change
@@ -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"
Expand All @@ -15,5 +13,3 @@
#include "AP_MotorsHeli_Single.h"
#include "AP_MotorsSingle.h"
#include "AP_MotorsCoax.h"

#endif // __AP_MOTORS_H__
6 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsCoax.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -71,5 +69,3 @@ class AP_MotorsCoax : public AP_MotorsMulticopter {
RC_Channel& _servo1;
RC_Channel& _servo2;
};

#endif // AP_MOTORSCOAX
6 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsHeli.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand Down Expand Up @@ -246,5 +244,3 @@ class AP_MotorsHeli : public AP_Motors {
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 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsHeli_RSC.h
Original file line number Diff line number Diff line change
@@ -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
Expand Down Expand Up @@ -118,5 +116,3 @@ class AP_MotorsHeli_RSC {
// 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 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsHeli_Single.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -186,5 +184,3 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli {

bool _acro_tail = false;
};

#endif // __AP_MOTORS_HELI_SINGLE_H__
6 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsHexa.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -26,5 +24,3 @@ class AP_MotorsHexa : public AP_MotorsMatrix {
protected:

};

#endif // AP_MOTORSHEXA
6 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsMatrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -79,5 +77,3 @@ class AP_MotorsMatrix : public AP_MotorsMulticopter {
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 changes: 1 addition & 4 deletions libraries/AP_Motors/AP_MotorsMulticopter.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"

Expand Down Expand Up @@ -177,4 +175,3 @@ class AP_MotorsMulticopter : public AP_Motors {
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 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsOcta.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -26,5 +24,3 @@ class AP_MotorsOcta : public AP_MotorsMatrix {
protected:

};

#endif // AP_MOTORSOCTA
6 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsOctaQuad.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -26,5 +24,3 @@ class AP_MotorsOctaQuad : public AP_MotorsMatrix {
protected:

};

#endif // AP_MOTORSOCTAQUAD
6 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsQuad.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -26,5 +24,3 @@ class AP_MotorsQuad : public AP_MotorsMatrix {
protected:

};

#endif // AP_MOTORSQUAD
6 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsSingle.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -74,5 +72,3 @@ class AP_MotorsSingle : public AP_MotorsMulticopter {
RC_Channel& _servo3;
RC_Channel& _servo4;
};

#endif // AP_MOTORSSINGLE
6 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsTri.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -64,5 +62,3 @@ class AP_MotorsTri : public AP_MotorsMulticopter {
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 changes: 1 addition & 5 deletions libraries/AP_Motors/AP_MotorsY6.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -28,5 +26,3 @@ class AP_MotorsY6 : public AP_MotorsMatrix {
protected:

};

#endif // AP_MOTORSY6
5 changes: 1 addition & 4 deletions libraries/AP_Motors/AP_Motors_Class.h
Original file line number Diff line number Diff line change
@@ -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
Expand Down Expand Up @@ -169,4 +167,3 @@ class AP_Motors {
uint8_t _motor_map[AP_MOTORS_MAX_NUM_MOTORS];
uint16_t _motor_map_mask;
};
#endif // __AP_MOTORS_CLASS_H__

0 comments on commit 7d9153f

Please sign in to comment.