mirror of https://github.com/ArduPilot/ardupilot
AC_PID: standardize inclusion of libaries headers
This commit changes the way libraries headers are included in source files: - If the header is in the same directory the source belongs to, so the notation '#include ""' is used with the path relative to the directory containing the source. - If the header is outside the directory containing the source, then we use the notation '#include <>' with the path relative to libraries folder. Some of the advantages of such approach: - Only one search path for libraries headers. - OSs like Windows may have a better lookup time.
This commit is contained in:
parent
d030e817d9
commit
286d084d83
|
@ -3,7 +3,7 @@
|
||||||
/// @file AC_HELI_PID.cpp
|
/// @file AC_HELI_PID.cpp
|
||||||
/// @brief Generic PID algorithm
|
/// @brief Generic PID algorithm
|
||||||
|
|
||||||
#include <AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include "AC_HELI_PID.h"
|
#include "AC_HELI_PID.h"
|
||||||
|
|
||||||
const AP_Param::GroupInfo AC_HELI_PID::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AC_HELI_PID::var_info[] PROGMEM = {
|
||||||
|
|
|
@ -6,11 +6,11 @@
|
||||||
#ifndef __AC_HELI_PID_H__
|
#ifndef __AC_HELI_PID_H__
|
||||||
#define __AC_HELI_PID_H__
|
#define __AC_HELI_PID_H__
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <AC_PID.h>
|
#include "AC_PID.h"
|
||||||
|
|
||||||
/// @class AC_HELI_PID
|
/// @class AC_HELI_PID
|
||||||
/// @brief Heli PID control class
|
/// @brief Heli PID control class
|
||||||
|
|
|
@ -3,7 +3,7 @@
|
||||||
/// @file AC_P.cpp
|
/// @file AC_P.cpp
|
||||||
/// @brief Generic P algorithm
|
/// @brief Generic P algorithm
|
||||||
|
|
||||||
#include <AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include "AC_P.h"
|
#include "AC_P.h"
|
||||||
|
|
||||||
const AP_Param::GroupInfo AC_P::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AC_P::var_info[] PROGMEM = {
|
||||||
|
|
|
@ -6,8 +6,8 @@
|
||||||
#ifndef __AC_P_H__
|
#ifndef __AC_P_H__
|
||||||
#define __AC_P_H__
|
#define __AC_P_H__
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
|
|
|
@ -3,7 +3,7 @@
|
||||||
/// @file AC_PID.cpp
|
/// @file AC_PID.cpp
|
||||||
/// @brief Generic PID algorithm
|
/// @brief Generic PID algorithm
|
||||||
|
|
||||||
#include <AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include "AC_PID.h"
|
#include "AC_PID.h"
|
||||||
|
|
||||||
const AP_Param::GroupInfo AC_PID::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AC_PID::var_info[] PROGMEM = {
|
||||||
|
|
|
@ -6,11 +6,11 @@
|
||||||
#ifndef __AC_PID_H__
|
#ifndef __AC_PID_H__
|
||||||
#define __AC_PID_H__
|
#define __AC_PID_H__
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <DataFlash.h>
|
#include <DataFlash/DataFlash.h>
|
||||||
|
|
||||||
#define AC_PID_FILT_HZ_DEFAULT 20.0f // default input filter frequency
|
#define AC_PID_FILT_HZ_DEFAULT 20.0f // default input filter frequency
|
||||||
#define AC_PID_FILT_HZ_MIN 0.01f // minimum input filter frequency
|
#define AC_PID_FILT_HZ_MIN 0.01f // minimum input filter frequency
|
||||||
|
|
|
@ -3,7 +3,7 @@
|
||||||
/// @file AC_PI_2D.cpp
|
/// @file AC_PI_2D.cpp
|
||||||
/// @brief Generic PID algorithm
|
/// @brief Generic PID algorithm
|
||||||
|
|
||||||
#include <AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include "AC_PI_2D.h"
|
#include "AC_PI_2D.h"
|
||||||
|
|
||||||
const AP_Param::GroupInfo AC_PI_2D::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AC_PI_2D::var_info[] PROGMEM = {
|
||||||
|
|
|
@ -6,8 +6,8 @@
|
||||||
#ifndef __AC_PI_2D_H__
|
#ifndef __AC_PI_2D_H__
|
||||||
#define __AC_PI_2D_H__
|
#define __AC_PI_2D_H__
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
|
|
|
@ -3,40 +3,40 @@
|
||||||
* 2012 Code by Jason Short, Randy Mackay. DIYDrones.com
|
* 2012 Code by Jason Short, Randy Mackay. DIYDrones.com
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Progmem.h>
|
#include <AP_Progmem/AP_Progmem.h>
|
||||||
#include <AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||||
#include <AP_HAL_SITL.h>
|
#include <AP_HAL_SITL/AP_HAL_SITL.h>
|
||||||
#include <AP_HAL_Linux.h>
|
#include <AP_HAL_Linux/AP_HAL_Linux.h>
|
||||||
#include <AP_HAL_FLYMAPLE.h>
|
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
|
||||||
#include <AP_HAL_PX4.h>
|
#include <AP_HAL_PX4/AP_HAL_PX4.h>
|
||||||
#include <AP_HAL_Empty.h>
|
#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
||||||
#include <GCS_MAVLink.h>
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
#include <StorageManager.h>
|
#include <StorageManager/StorageManager.h>
|
||||||
#include <AC_PID.h>
|
#include <AC_PID/AC_PID.h>
|
||||||
#include <AC_HELI_PID.h>
|
#include <AC_PID/AC_HELI_PID.h>
|
||||||
#include <AP_Scheduler.h>
|
#include <AP_Scheduler/AP_Scheduler.h>
|
||||||
#include <DataFlash.h>
|
#include <DataFlash/DataFlash.h>
|
||||||
#include <AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_Vehicle.h>
|
#include <AP_Vehicle/AP_Vehicle.h>
|
||||||
#include <AP_InertialSensor.h>
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||||
#include <Filter.h>
|
#include <Filter/Filter.h>
|
||||||
#include <AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
#include <AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Compass.h>
|
#include <AP_Compass/AP_Compass.h>
|
||||||
#include <AP_Declination.h>
|
#include <AP_Declination/AP_Declination.h>
|
||||||
#include <AP_Airspeed.h>
|
#include <AP_Airspeed/AP_Airspeed.h>
|
||||||
#include <AP_NavEKF.h>
|
#include <AP_NavEKF/AP_NavEKF.h>
|
||||||
#include <AP_ADC.h>
|
#include <AP_ADC/AP_ADC.h>
|
||||||
#include <AP_ADC_AnalogSource.h>
|
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
||||||
#include <AP_Notify.h>
|
#include <AP_Notify/AP_Notify.h>
|
||||||
#include <AP_Mission.h>
|
#include <AP_Mission/AP_Mission.h>
|
||||||
#include <AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
#include <AP_Rally.h>
|
#include <AP_Rally/AP_Rally.h>
|
||||||
#include <AP_RangeFinder.h>
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue