mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_AVR: 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
98a772c323
commit
a80ae0cde3
|
@ -2,7 +2,7 @@
|
|||
#ifndef __AP_HAL_AVR_H__
|
||||
#define __AP_HAL_AVR_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
/**
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#ifndef __AP_HAL_AVR_ANALOG_IN_H__
|
||||
#define __AP_HAL_AVR_ANALOG_IN_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
#define AVR_INPUT_MAX_CHANNELS 12
|
||||
|
|
|
@ -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_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/io.h>
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
/// -*- 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_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AnalogIn.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/interrupt.h>
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#ifndef __AP_HAL_AVR_GPIO_H__
|
||||
#define __AP_HAL_AVR_GPIO_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
/* To save linker space, we need to make sure the HAL_AVR_APM1 class
|
||||
* is built iff we are building for HAL_BOARD_APM1. These defines must
|
||||
* wrap the whole HAL_AVR_APM1 class declaration and definition. */
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include "AP_HAL_AVR.h"
|
||||
#include "AP_HAL_AVR_private.h"
|
||||
#include "HAL_AVR_APM1_Class.h"
|
||||
|
||||
|
|
|
@ -2,14 +2,14 @@
|
|||
#ifndef __AP_HAL_AVR_APM1_HAL_AVR_H__
|
||||
#define __AP_HAL_AVR_APM1_HAL_AVR_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
/* To save linker space, we need to make sure the HAL_AVR_APM1 class
|
||||
* is built iff we are building for HAL_BOARD_APM1. These defines must
|
||||
* wrap the whole HAL_AVR_APM1 class declaration and definition. */
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include "AP_HAL_AVR.h"
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
/**
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
/* To save linker space, we need to make sure the HAL_AVR_APM2 class
|
||||
* is built iff we are building for HAL_BOARD_APM2. These defines must
|
||||
* wrap the whole HAL_AVR_APM2 class declaration and definition. */
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include "AP_HAL_AVR.h"
|
||||
#include "AP_HAL_AVR_private.h"
|
||||
#include "HAL_AVR_APM2_Class.h"
|
||||
|
||||
|
|
|
@ -2,14 +2,14 @@
|
|||
#ifndef __AP_HAL_AVR_APM2_HAL_AVR_H__
|
||||
#define __AP_HAL_AVR_APM2_HAL_AVR_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
/* To save linker space, we need to make sure the HAL_AVR_APM2 class
|
||||
* is built iff we are building for HAL_BOARD_APM2. These defines must
|
||||
* wrap the whole HAL_AVR_APM2 class declaration and definition. */
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include "AP_HAL_AVR.h"
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
/**
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <inttypes.h>
|
||||
|
@ -41,7 +41,7 @@
|
|||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "I2CDriver.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#ifndef __AP_HAL_AVR_I2C_DRIVER_H__
|
||||
#define __AP_HAL_AVR_I2C_DRIVER_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
#define AVRI2CDRIVER_MAX_BUFFER_SIZE 32
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#ifndef __AP_HAL_AVR_RC_INPUT_H__
|
||||
#define __AP_HAL_AVR_RC_INPUT_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
#define AVR_RC_INPUT_NUM_CHANNELS 11
|
||||
|
|
|
@ -1,11 +1,11 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR.h"
|
||||
#include "RCInput.h"
|
||||
#include "utility/ISRRegistry.h"
|
||||
using namespace AP_HAL;
|
||||
|
|
|
@ -1,11 +1,11 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR.h"
|
||||
#include "RCInput.h"
|
||||
#include "utility/ISRRegistry.h"
|
||||
using namespace AP_HAL;
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#ifndef __AP_HAL_AVR_RC_OUTPUT_H__
|
||||
#define __AP_HAL_AVR_RC_OUTPUT_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
class AP_HAL_AVR::APM1RCOutput : public AP_HAL::RCOutput {
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR.h"
|
||||
#include "RCOutput.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR.h"
|
||||
#include "RCOutput.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "SPIDriver.h"
|
||||
#include "SPIDevices.h"
|
||||
#include "GPIO.h"
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "SPIDriver.h"
|
||||
#include "SPIDevices.h"
|
||||
#include "utility/pins_arduino_mega.h"
|
||||
|
|
|
@ -1,9 +1,9 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "SPIDevices.h"
|
||||
#include "GPIO.h"
|
||||
#include "Semaphores.h"
|
||||
|
|
|
@ -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_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "SPIDevices.h"
|
||||
#include "GPIO.h"
|
||||
#include "Semaphores.h"
|
||||
|
|
|
@ -1,11 +1,11 @@
|
|||
/// -*- 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_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "SPIDevices.h"
|
||||
#include "GPIO.h"
|
||||
#include "Semaphores.h"
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#ifndef __AP_HAL_AVR_SPI_DEVICES_H__
|
||||
#define __AP_HAL_AVR_SPI_DEVICES_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
class AP_HAL_AVR::AVRSPI0DeviceDriver : public AP_HAL::SPIDeviceDriver {
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#ifndef __AP_HAL_AVR_SPI_DRIVER_H__
|
||||
#define __AP_HAL_AVR_SPI_DRIVER_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
#include "GPIO.h"
|
||||
#include "SPIDevices.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_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/io.h>
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#ifndef __AP_HAL_AVR_SCHEDULER_H__
|
||||
#define __AP_HAL_AVR_SCHEDULER_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
#define AVR_SCHEDULER_MAX_TIMER_PROCS 4
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/io.h>
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
/// -*- 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_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR.h"
|
||||
#include "Semaphores.h"
|
||||
#include "Scheduler.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
#ifndef __AP_HAL_AVR_SEMAPHORES_H__
|
||||
#define __AP_HAL_AVR_SEMAPHORES_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR_Namespace.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
class AP_HAL_AVR::AVRSemaphore : public AP_HAL::Semaphore {
|
||||
public:
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <avr/io.h>
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
#ifndef __AP_HAL_AVR_STORAGE_H__
|
||||
#define __AP_HAL_AVR_STORAGE_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
class AP_HAL_AVR::AVREEPROMStorage : public AP_HAL::Storage {
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
//
|
||||
// Copyright (c) 2010 Michael Smith. All rights reserved.
|
||||
//
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <limits.h>
|
||||
|
@ -26,8 +26,8 @@
|
|||
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include "UARTDriver.h"
|
||||
|
||||
using namespace AP_HAL_AVR;
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
|
||||
#ifndef __AP_HAL_AVR_UART_DRIVER_H__
|
||||
#define __AP_HAL_AVR_UART_DRIVER_H__
|
||||
#include <AP_HAL_Boards.h>
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <stdint.h>
|
||||
|
@ -9,7 +9,7 @@
|
|||
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
/**
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#ifndef __AP_HAL_AVR_UTIL_H__
|
||||
#define __AP_HAL_AVR_UTIL_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
#include "memcheck.h"
|
||||
|
||||
|
|
|
@ -1,48 +1,48 @@
|
|||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.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_Common.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Menu.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_GPS.h> // ArduPilot GPS library
|
||||
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <AP_Baro.h>
|
||||
#include <AP_Declination.h>
|
||||
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_Curve.h> // Curve used to linearlise throttle pwm to thrust
|
||||
#include <AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
#include <AP_Menu/AP_Menu.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
|
||||
#include <AP_ADC/AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
#include <AP_Declination/AP_Declination.h>
|
||||
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_Curve/AP_Curve.h> // Curve used to linearlise throttle pwm to thrust
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
||||
// (only included for makefile libpath to work)
|
||||
#include <AP_AHRS.h>
|
||||
#include <AC_PID.h> // PID library
|
||||
#include <AC_P.h> // P library
|
||||
#include <RC_Channel.h> // RC Channel Library
|
||||
#include <AP_Motors.h> // AP Motors library
|
||||
#include <AP_ADC_AnalogSource.h>
|
||||
#include <AP_RangeFinder.h> // Range finder library
|
||||
#include <AP_OpticalFlow.h> // Optical Flow library
|
||||
#include <Filter.h> // Filter library
|
||||
#include <AP_Buffer.h> // APM FIFO Buffer
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <AP_Camera.h> // Photo or video camera
|
||||
#include <AP_Mount.h> // Camera/Antenna mount
|
||||
#include <AP_Airspeed.h> // needed for AHRS build
|
||||
#include <AP_Vehicle.h> // needed for AHRS build
|
||||
#include <AP_Notify.h>
|
||||
#include <DataFlash.h>
|
||||
#include <AP_InertialNav.h> // ArduPilot Mega inertial navigation library
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <AP_Mission.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Terrain.h>
|
||||
#include <memcheck.h>
|
||||
#include <AP_NavEKF.h>
|
||||
#include <AP_Nav_Common.h>
|
||||
#include <AP_BattMonitor.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AC_PID/AC_PID.h> // PID library
|
||||
#include <AC_PID/AC_P.h> // P library
|
||||
#include <RC_Channel/RC_Channel.h> // RC Channel Library
|
||||
#include <AP_Motors/AP_Motors.h> // AP Motors library
|
||||
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
|
||||
#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
|
||||
#include <Filter/Filter.h> // Filter library
|
||||
#include <AP_Buffer/AP_Buffer.h> // APM FIFO Buffer
|
||||
#include <AP_Relay/AP_Relay.h> // APM relay
|
||||
#include <AP_Camera/AP_Camera.h> // Photo or video camera
|
||||
#include <AP_Mount/AP_Mount.h> // Camera/Antenna mount
|
||||
#include <AP_Airspeed/AP_Airspeed.h> // needed for AHRS build
|
||||
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <DataFlash/DataFlash.h>
|
||||
#include <AP_InertialNav/AP_InertialNav.h> // ArduPilot Mega inertial navigation library
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_Mission/AP_Mission.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <AP_HAL_AVR/memcheck.h>
|
||||
#include <AP_NavEKF/AP_NavEKF.h>
|
||||
#include <AP_NavEKF/AP_Nav_Common.h>
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
|
|
@ -1,42 +1,42 @@
|
|||
|
||||
|
||||
// Libraries
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Menu.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_GPS.h> // ArduPilot GPS library
|
||||
#include <AP_Baro.h> // ArduPilot barometer library
|
||||
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <AP_InertialSensor.h> // Inertial Sensor Library
|
||||
#include <AP_AHRS.h> // ArduPilot Mega DCM Library
|
||||
#include <PID.h> // PID library
|
||||
#include <RC_Channel.h> // RC Channel Library
|
||||
#include <AP_ADC_AnalogSource.h>
|
||||
#include <AP_RangeFinder.h> // Range finder library
|
||||
#include <Filter.h> // Filter library
|
||||
#include <AP_Buffer.h> // APM FIFO Buffer
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <AP_Camera.h> // Photo or video camera
|
||||
#include <AP_Airspeed.h>
|
||||
#include <AP_Notify.h>
|
||||
#include <memcheck.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
#include <AP_Menu/AP_Menu.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
|
||||
#include <AP_Baro/AP_Baro.h> // ArduPilot barometer library
|
||||
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_ADC/AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h> // Inertial Sensor Library
|
||||
#include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library
|
||||
#include <PID/PID.h> // PID library
|
||||
#include <RC_Channel/RC_Channel.h> // RC Channel Library
|
||||
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
|
||||
#include <Filter/Filter.h> // Filter library
|
||||
#include <AP_Buffer/AP_Buffer.h> // APM FIFO Buffer
|
||||
#include <AP_Relay/AP_Relay.h> // APM relay
|
||||
#include <AP_Camera/AP_Camera.h> // Photo or video camera
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <AP_HAL_AVR/memcheck.h>
|
||||
|
||||
#include <DataFlash.h>
|
||||
#include <APM_Control.h>
|
||||
#include <AP_Vehicle.h>
|
||||
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
#include <AP_Mission.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Terrain.h>
|
||||
#include <AP_Mount.h> // Camera/Antenna mount
|
||||
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <AP_BattMonitor.h>
|
||||
#include <DataFlash/DataFlash.h>
|
||||
#include <APM_Control/APM_Control.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
#include <AP_Mission/AP_Mission.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <AP_Mount/AP_Mount.h> // Camera/Antenna mount
|
||||
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
|
|
|
@ -6,14 +6,14 @@
|
|||
// This code is placed into the public domain.
|
||||
//
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
|
|
@ -4,14 +4,14 @@
|
|||
* the three axis of data.
|
||||
*******************************************/
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
|
|
@ -37,13 +37,13 @@
|
|||
|
||||
// include the library code:
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#include "LCrystal.h"
|
||||
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
#include <string.h>
|
||||
#include <inttypes.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
|
|
@ -1,11 +1,11 @@
|
|||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
|
|
@ -4,14 +4,14 @@
|
|||
* temperature, three axis of gyro data
|
||||
*******************************************/
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
/* register #defines */
|
||||
#include "MPU6000.h"
|
||||
|
|
|
@ -1,11 +1,11 @@
|
|||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
|
|
@ -6,14 +6,14 @@
|
|||
// This code is placed into the public domain.
|
||||
//
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
|
|
@ -2,14 +2,14 @@
|
|||
|
||||
#include <string.h>
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
* of false positives with uninitialised stack variables
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include <AP_HAL.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||
|
||||
#include <stdlib.h>
|
||||
|
|
|
@ -3,8 +3,8 @@
|
|||
#ifndef __AP_HAL_AVR_ISR_REGISTRY_H__
|
||||
#define __AP_HAL_AVR_ISR_REGISTRY_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR_Namespace.h>
|
||||
|
||||
#define ISR_REGISTRY_TIMER2_OVF 0
|
||||
#define ISR_REGISTRY_TIMER4_CAPT 1
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include <AP_HAL_Boards.h>
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
|
||||
#include <avr/io.h>
|
||||
|
|
Loading…
Reference in New Issue