AP_HAL_PX4: 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
124b750c10
commit
08333f1ffe
@ -2,7 +2,7 @@
|
||||
#ifndef __AP_HAL_PX4_H__
|
||||
#define __AP_HAL_PX4_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include "HAL_PX4_Class.h"
|
||||
|
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include "AnalogIn.h"
|
||||
@ -16,7 +16,7 @@
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/servorail_status.h>
|
||||
#include <uORB/topics/system_power.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <errno.h>
|
||||
#include "GPIO.h"
|
||||
|
||||
|
@ -3,7 +3,7 @@
|
||||
#ifndef __AP_HAL_PX4_ANALOGIN_H__
|
||||
#define __AP_HAL_PX4_ANALOGIN_H__
|
||||
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include "AP_HAL_PX4.h"
|
||||
#include <pthread.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
|
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
|
||||
|
@ -3,7 +3,7 @@
|
||||
#ifndef __AP_HAL_PX4_GPIO_H__
|
||||
#define __AP_HAL_PX4_GPIO_H__
|
||||
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include "AP_HAL_PX4.h"
|
||||
|
||||
#define PX4_GPIO_PIEZO_PIN 110
|
||||
#define PX4_GPIO_EXT_FMU_RELAY1_PIN 111
|
||||
|
@ -1,10 +1,10 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include "AP_HAL_PX4.h"
|
||||
#include "AP_HAL_PX4_Namespace.h"
|
||||
#include "HAL_PX4_Class.h"
|
||||
#include "Scheduler.h"
|
||||
@ -16,8 +16,8 @@
|
||||
#include "Util.h"
|
||||
#include "GPIO.h"
|
||||
|
||||
#include <AP_HAL_Empty.h>
|
||||
#include <AP_HAL_Empty_Private.h>
|
||||
#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
||||
#include <AP_HAL_Empty/AP_HAL_Empty_Private.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
@ -2,11 +2,11 @@
|
||||
#ifndef __AP_HAL_PX4_CLASS_H__
|
||||
#define __AP_HAL_PX4_CLASS_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include "AP_HAL_PX4.h"
|
||||
#include "AP_HAL_PX4_Namespace.h"
|
||||
#include <systemlib/visibility.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
@ -5,7 +5,7 @@
|
||||
See GCS_serial_control.cpp for usage
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include <stdio.h>
|
||||
#include <stdarg.h>
|
||||
|
@ -1,4 +1,4 @@
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include "RCInput.h"
|
||||
|
@ -2,7 +2,7 @@
|
||||
#ifndef __AP_HAL_PX4_RCINPUT_H__
|
||||
#define __AP_HAL_PX4_RCINPUT_H__
|
||||
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include "AP_HAL_PX4.h"
|
||||
#include <drivers/drv_rc_input.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <pthread.h>
|
||||
|
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include "RCOutput.h"
|
||||
|
@ -2,7 +2,7 @@
|
||||
#ifndef __AP_HAL_PX4_RCOUTPUT_H__
|
||||
#define __AP_HAL_PX4_RCOUTPUT_H__
|
||||
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include "AP_HAL_PX4.h"
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <uORB/topics/actuator_outputs.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
|
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
|
||||
#include "AP_HAL_PX4.h"
|
||||
@ -22,7 +22,7 @@
|
||||
#include "Storage.h"
|
||||
#include "RCOutput.h"
|
||||
#include "RCInput.h"
|
||||
#include <AP_Scheduler.h>
|
||||
#include <AP_Scheduler/AP_Scheduler.h>
|
||||
|
||||
using namespace PX4;
|
||||
|
||||
|
@ -2,7 +2,7 @@
|
||||
#ifndef __AP_HAL_PX4_SCHEDULER_H__
|
||||
#define __AP_HAL_PX4_SCHEDULER_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include "AP_HAL_PX4_Namespace.h"
|
||||
#include <sys/time.h>
|
||||
|
@ -1,4 +1,4 @@
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
|
||||
#include <assert.h>
|
||||
|
@ -3,7 +3,7 @@
|
||||
#ifndef __AP_HAL_PX4_STORAGE_H__
|
||||
#define __AP_HAL_PX4_STORAGE_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_PX4_Namespace.h"
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
|
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include "UARTDriver.h"
|
||||
|
@ -2,7 +2,7 @@
|
||||
#ifndef __AP_HAL_PX4_UARTDRIVER_H__
|
||||
#define __AP_HAL_PX4_UARTDRIVER_H__
|
||||
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include "AP_HAL_PX4.h"
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
class PX4::PX4UARTDriver : public AP_HAL::UARTDriver {
|
||||
|
@ -1,5 +1,5 @@
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include <stdio.h>
|
||||
#include <stdarg.h>
|
||||
|
@ -2,7 +2,7 @@
|
||||
#ifndef __AP_HAL_PX4_UTIL_H__
|
||||
#define __AP_HAL_PX4_UTIL_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_PX4_Namespace.h"
|
||||
|
||||
class PX4::NSHShellStream : public AP_HAL::Stream {
|
||||
|
@ -5,39 +5,39 @@
|
||||
Andrew Tridgell September 2011
|
||||
*/
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL_SITL.h>
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include <AP_HAL_Empty.h>
|
||||
#include <AP_Math.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_InertialSensor.h>
|
||||
#include <AP_ADC.h>
|
||||
#include <AP_InertialSensor.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <DataFlash.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <AP_Mission.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Terrain.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Baro.h>
|
||||
#include <AP_Compass.h>
|
||||
#include <AP_Declination.h>
|
||||
#include <SITL.h>
|
||||
#include <AP_Notify.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_Airspeed.h>
|
||||
#include <AP_Vehicle.h>
|
||||
#include <AP_ADC_AnalogSource.h>
|
||||
#include <AP_Rally.h>
|
||||
#include <AP_NavEKF.h>
|
||||
#include <AP_BattMonitor.h>
|
||||
#include <AP_Scheduler.h>
|
||||
#include <AP_RangeFinder.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
#include <AP_HAL_SITL/AP_HAL_SITL.h>
|
||||
#include <AP_HAL_PX4/AP_HAL_PX4.h>
|
||||
#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <Filter/Filter.h>
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
#include <AP_ADC/AP_ADC.h>
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <DataFlash/DataFlash.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_Mission/AP_Mission.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
#include <AP_Compass/AP_Compass.h>
|
||||
#include <AP_Declination/AP_Declination.h>
|
||||
#include <SITL/SITL.h>
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
||||
#include <AP_Rally/AP_Rally.h>
|
||||
#include <AP_NavEKF/AP_NavEKF.h>
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||
#include <AP_Scheduler/AP_Scheduler.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
|
@ -6,7 +6,7 @@
|
||||
try to access FRAM in an invalid manner
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include <px4_defines.h>
|
||||
|
Loading…
Reference in New Issue
Block a user