AP_Airspeed: 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:
Gustavo Jose de Sousa 2015-08-11 16:28:42 +10:00 committed by Randy Mackay
parent 7b2facf717
commit 8fb7098903
12 changed files with 72 additions and 72 deletions

View File

@ -18,16 +18,16 @@
*/ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_ADC.h> #include <AP_ADC/AP_ADC.h>
#include <AP_Airspeed.h> #include "AP_Airspeed.h"
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 #if CONFIG_HAL_BOARD == HAL_BOARD_APM1
#include <AP_ADC_AnalogSource.h> #include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#define ARSPD_DEFAULT_PIN 64 #define ARSPD_DEFAULT_PIN 64
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 #elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
#define ARSPD_DEFAULT_PIN 0 #define ARSPD_DEFAULT_PIN 0

View File

@ -3,15 +3,15 @@
#ifndef __AP_AIRSPEED_H__ #ifndef __AP_AIRSPEED_H__
#define __AP_AIRSPEED_H__ #define __AP_AIRSPEED_H__
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Param.h> #include <AP_Param/AP_Param.h>
#include <GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Vehicle.h> #include <AP_Vehicle/AP_Vehicle.h>
#include <AP_Airspeed_Backend.h> #include "AP_Airspeed_Backend.h"
#include <AP_Airspeed_analog.h> #include "AP_Airspeed_analog.h"
#include <AP_Airspeed_PX4.h> #include "AP_Airspeed_PX4.h"
#include <AP_Airspeed_I2C.h> #include "AP_Airspeed_I2C.h"
class Airspeed_Calibration { class Airspeed_Calibration {
public: public:

View File

@ -22,8 +22,8 @@
#ifndef __AP_AIRSPEED_BACKEND_H__ #ifndef __AP_AIRSPEED_BACKEND_H__
#define __AP_AIRSPEED_BACKEND_H__ #define __AP_AIRSPEED_BACKEND_H__
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
class AP_Airspeed_Backend { class AP_Airspeed_Backend {
public: public:

View File

@ -19,10 +19,10 @@
backend driver for airspeed from a I2C MS4525D0 sensor backend driver for airspeed from a I2C MS4525D0 sensor
*/ */
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_Airspeed_I2C.h> #include "AP_Airspeed_I2C.h"
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;

View File

@ -22,8 +22,8 @@
#ifndef __AP_AIRSPEED_I2C_H__ #ifndef __AP_AIRSPEED_I2C_H__
#define __AP_AIRSPEED_I2C_H__ #define __AP_AIRSPEED_I2C_H__
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Airspeed_Backend.h> #include "AP_Airspeed_Backend.h"
class AP_Airspeed_I2C : public AP_Airspeed_Backend class AP_Airspeed_I2C : public AP_Airspeed_Backend
{ {

View File

@ -22,8 +22,8 @@
#ifndef __AP_AIRSPEED_I2C_H__ #ifndef __AP_AIRSPEED_I2C_H__
#define __AP_AIRSPEED_I2C_H__ #define __AP_AIRSPEED_I2C_H__
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
class AP_Airspeed_I2C_PX4 : AP_Airspeed_I2C { class AP_Airspeed_I2C_PX4 : AP_Airspeed_I2C {
public: public:

View File

@ -18,11 +18,11 @@
*/ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
#include <AP_Airspeed_PX4.h> #include "AP_Airspeed_PX4.h"
#include <drivers/drv_airspeed.h> #include <drivers/drv_airspeed.h>
#include <uORB/topics/differential_pressure.h> #include <uORB/topics/differential_pressure.h>
#include <sys/types.h> #include <sys/types.h>

View File

@ -22,8 +22,8 @@
#ifndef __AP_AIRSPEED_PX4_H__ #ifndef __AP_AIRSPEED_PX4_H__
#define __AP_AIRSPEED_PX4_H__ #define __AP_AIRSPEED_PX4_H__
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Airspeed_Backend.h> #include "AP_Airspeed_Backend.h"
class AP_Airspeed_PX4 : public AP_Airspeed_Backend { class AP_Airspeed_PX4 : public AP_Airspeed_Backend {
public: public:

View File

@ -18,12 +18,12 @@
*/ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_Common.h> #include <AP_Common/AP_Common.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_Airspeed.h> #include "AP_Airspeed.h"
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;

View File

@ -3,8 +3,8 @@
#ifndef __AP_AIRSPEED_ANALOG_H__ #ifndef __AP_AIRSPEED_ANALOG_H__
#define __AP_AIRSPEED_ANALOG_H__ #define __AP_AIRSPEED_ANALOG_H__
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Airspeed_Backend.h> #include "AP_Airspeed_Backend.h"
class AP_Airspeed_Analog : public AP_Airspeed_Backend class AP_Airspeed_Analog : public AP_Airspeed_Backend
{ {

View File

@ -6,10 +6,10 @@
* *
*/ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Airspeed.h> #include "AP_Airspeed.h"
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;

View File

@ -19,37 +19,37 @@
* *
*/ */
#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_Linux.h> #include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty/AP_HAL_Empty.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 <Filter.h> #include <Filter/Filter.h>
#include <AP_Buffer.h> #include <AP_Buffer/AP_Buffer.h>
#include <AP_Airspeed.h> #include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle.h> #include <AP_Vehicle/AP_Vehicle.h>
#include <AP_Notify.h> #include <AP_Notify/AP_Notify.h>
#include <AP_Compass.h> #include <AP_Compass/AP_Compass.h>
#include <AP_Declination.h> #include <AP_Declination/AP_Declination.h>
#include <AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_NavEKF.h> #include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Terrain.h> #include <AP_Terrain/AP_Terrain.h>
#include <DataFlash.h> #include <DataFlash/DataFlash.h>
#include <AP_Baro.h> #include <AP_Baro/AP_Baro.h>
#include <GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission.h> #include <AP_Mission/AP_Mission.h>
#include <StorageManager.h> #include <StorageManager/StorageManager.h>
#include <AP_Terrain.h> #include <AP_Terrain/AP_Terrain.h>
#include <AP_GPS.h> #include <AP_GPS/AP_GPS.h>
#include <AP_InertialSensor.h> #include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_Rally.h> #include <AP_Rally/AP_Rally.h>
#include <AP_RangeFinder.h> #include <AP_RangeFinder/AP_RangeFinder.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 #if CONFIG_HAL_BOARD == HAL_BOARD_APM1
AP_ADC_ADS7844 apm1_adc; AP_ADC_ADS7844 apm1_adc;