mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AP_Motors: replace header guard with pragma once
This commit is contained in:
parent
d82e80c749
commit
7d9153feb8
@ -1,7 +1,5 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_H__
|
|
||||||
#define __AP_MOTORS_H__
|
|
||||||
|
|
||||||
#include "AP_Motors_Class.h"
|
#include "AP_Motors_Class.h"
|
||||||
#include "AP_MotorsMulticopter.h"
|
#include "AP_MotorsMulticopter.h"
|
||||||
@ -15,5 +13,3 @@
|
|||||||
#include "AP_MotorsHeli_Single.h"
|
#include "AP_MotorsHeli_Single.h"
|
||||||
#include "AP_MotorsSingle.h"
|
#include "AP_MotorsSingle.h"
|
||||||
#include "AP_MotorsCoax.h"
|
#include "AP_MotorsCoax.h"
|
||||||
|
|
||||||
#endif // __AP_MOTORS_H__
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsCoax.h
|
/// @file AP_MotorsCoax.h
|
||||||
/// @brief Motor and Servo control class for Co-axial helicopters with two motors and two flaps
|
/// @brief Motor and Servo control class for Co-axial helicopters with two motors and two flaps
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_COAX_H__
|
|
||||||
#define __AP_MOTORS_COAX_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -71,5 +69,3 @@ protected:
|
|||||||
RC_Channel& _servo1;
|
RC_Channel& _servo1;
|
||||||
RC_Channel& _servo2;
|
RC_Channel& _servo2;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSCOAX
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsHeli.h
|
/// @file AP_MotorsHeli.h
|
||||||
/// @brief Motor control class for Traditional Heli
|
/// @brief Motor control class for Traditional Heli
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_HELI_H__
|
|
||||||
#define __AP_MOTORS_HELI_H__
|
|
||||||
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
|
|
||||||
@ -246,5 +244,3 @@ protected:
|
|||||||
int16_t _collective_range = 0; // maximum absolute collective pitch range (500 - 1000)
|
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
|
uint8_t _servo_test_cycle_counter = 0; // number of test cycles left to run after bootup
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSHELI
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_HELI_RSC_H__
|
|
||||||
#define __AP_MOTORS_HELI_RSC_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -118,5 +116,3 @@ private:
|
|||||||
// write_rsc - outputs pwm onto output rsc channel. servo_out parameter is of the range 0 ~ 1000
|
// write_rsc - outputs pwm onto output rsc channel. servo_out parameter is of the range 0 ~ 1000
|
||||||
void write_rsc(int16_t servo_out);
|
void write_rsc(int16_t servo_out);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORS_HELI_RSC_H
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsHeli_Single.h
|
/// @file AP_MotorsHeli_Single.h
|
||||||
/// @brief Motor control class for traditional heli
|
/// @brief Motor control class for traditional heli
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_HELI_SINGLE_H__
|
|
||||||
#define __AP_MOTORS_HELI_SINGLE_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -186,5 +184,3 @@ protected:
|
|||||||
|
|
||||||
bool _acro_tail = false;
|
bool _acro_tail = false;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_MOTORS_HELI_SINGLE_H__
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsHexa.h
|
/// @file AP_MotorsHexa.h
|
||||||
/// @brief Motor control class for Hexacopters
|
/// @brief Motor control class for Hexacopters
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_HEXA_H__
|
|
||||||
#define __AP_MOTORS_HEXA_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -26,5 +24,3 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSHEXA
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsMatrix.h
|
/// @file AP_MotorsMatrix.h
|
||||||
/// @brief Motor control class for Matrixcopters
|
/// @brief Motor control class for Matrixcopters
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_MATRIX_H__
|
|
||||||
#define __AP_MOTORS_MATRIX_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -79,5 +77,3 @@ protected:
|
|||||||
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to yaw (normally 1 or -1)
|
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
|
uint8_t _test_order[AP_MOTORS_MAX_NUM_MOTORS]; // order of the motors in the test sequence
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSMATRIX
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsMulticopter.h
|
/// @file AP_MotorsMulticopter.h
|
||||||
/// @brief Motor control class for Multicopters
|
/// @brief Motor control class for Multicopters
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_MULTICOPTER_H__
|
|
||||||
#define __AP_MOTORS_MULTICOPTER_H__
|
|
||||||
|
|
||||||
#include "AP_Motors_Class.h"
|
#include "AP_Motors_Class.h"
|
||||||
|
|
||||||
@ -177,4 +175,3 @@ protected:
|
|||||||
float _lift_max; // maximum lift ratio from battery voltage
|
float _lift_max; // maximum lift ratio from battery voltage
|
||||||
float _throttle_limit; // ratio of throttle limit between hover and maximum
|
float _throttle_limit; // ratio of throttle limit between hover and maximum
|
||||||
};
|
};
|
||||||
#endif // __AP_MOTORS_MULTICOPTER_H__
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsOcta.h
|
/// @file AP_MotorsOcta.h
|
||||||
/// @brief Motor control class for Octacopters
|
/// @brief Motor control class for Octacopters
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_OCTA_H__
|
|
||||||
#define __AP_MOTORS_OCTA_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -26,5 +24,3 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSOCTA
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsOctaQuad.h
|
/// @file AP_MotorsOctaQuad.h
|
||||||
/// @brief Motor control class for OctaQuadcopters
|
/// @brief Motor control class for OctaQuadcopters
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_OCTA_QUAD_H__
|
|
||||||
#define __AP_MOTORS_OCTA_QUAD_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -26,5 +24,3 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSOCTAQUAD
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsQuad.h
|
/// @file AP_MotorsQuad.h
|
||||||
/// @brief Motor control class for Quadcopters
|
/// @brief Motor control class for Quadcopters
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_QUAD_H__
|
|
||||||
#define __AP_MOTORS_QUAD_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -26,5 +24,3 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSQUAD
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsSingle.h
|
/// @file AP_MotorsSingle.h
|
||||||
/// @brief Motor and Servo control class for Singlecopters
|
/// @brief Motor and Servo control class for Singlecopters
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_SING_H__
|
|
||||||
#define __AP_MOTORS_SING_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -74,5 +72,3 @@ protected:
|
|||||||
RC_Channel& _servo3;
|
RC_Channel& _servo3;
|
||||||
RC_Channel& _servo4;
|
RC_Channel& _servo4;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSSINGLE
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsTri.h
|
/// @file AP_MotorsTri.h
|
||||||
/// @brief Motor control class for Tricopters
|
/// @brief Motor control class for Tricopters
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_TRI_H__
|
|
||||||
#define __AP_MOTORS_TRI_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -64,5 +62,3 @@ protected:
|
|||||||
AP_Int16 _yaw_servo_min; // Minimum angle limit of yaw servo
|
AP_Int16 _yaw_servo_min; // Minimum angle limit of yaw servo
|
||||||
AP_Int16 _yaw_servo_max; // Maximum angle limit of yaw servo
|
AP_Int16 _yaw_servo_max; // Maximum angle limit of yaw servo
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSTRI
|
|
||||||
|
@ -2,9 +2,7 @@
|
|||||||
|
|
||||||
/// @file AP_MotorsY6.h
|
/// @file AP_MotorsY6.h
|
||||||
/// @brief Motor control class for Y6 frames
|
/// @brief Motor control class for Y6 frames
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_Y6_H__
|
|
||||||
#define __AP_MOTORS_Y6_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -28,5 +26,3 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSY6
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOTORS_CLASS_H__
|
|
||||||
#define __AP_MOTORS_CLASS_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -169,4 +167,3 @@ protected:
|
|||||||
uint8_t _motor_map[AP_MOTORS_MAX_NUM_MOTORS];
|
uint8_t _motor_map[AP_MOTORS_MAX_NUM_MOTORS];
|
||||||
uint16_t _motor_map_mask;
|
uint16_t _motor_map_mask;
|
||||||
};
|
};
|
||||||
#endif // __AP_MOTORS_CLASS_H__
|
|
||||||
|
Loading…
Reference in New Issue
Block a user