mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: 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
1e619c6c59
commit
8011579c5a
|
@ -1,14 +1,14 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_Gimbal.h>
|
||||
#include "AP_Gimbal.h"
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
||||
#include <stdio.h>
|
||||
#include <AP_Common.h>
|
||||
#include <GCS.h>
|
||||
#include <AP_SmallEKF.h>
|
||||
#include "AP_Math.h"
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_NavEKF/AP_SmallEKF.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
void AP_Gimbal::receive_feedback(mavlink_channel_t chan, mavlink_message_t *msg)
|
||||
{
|
||||
|
|
|
@ -9,18 +9,18 @@
|
|||
#ifndef __AP_GIMBAL_H__
|
||||
#define __AP_GIMBAL_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <AP_Mount.h>
|
||||
#include <AP_SmallEKF.h>
|
||||
#include <AP_NavEKF.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include "AP_Mount.h"
|
||||
#include <AP_NavEKF/AP_SmallEKF.h>
|
||||
#include <AP_NavEKF/AP_NavEKF.h>
|
||||
|
||||
class AP_Gimbal
|
||||
{
|
||||
|
|
|
@ -1,15 +1,15 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Mount.h>
|
||||
#include <AP_Mount_Backend.h>
|
||||
#include <AP_Mount_Servo.h>
|
||||
#include <AP_Mount_MAVLink.h>
|
||||
#include <AP_Mount_Alexmos.h>
|
||||
#include <AP_Mount_SToRM32.h>
|
||||
#include <AP_Mount_SToRM32_serial.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include "AP_Mount.h"
|
||||
#include "AP_Mount_Backend.h"
|
||||
#include "AP_Mount_Servo.h"
|
||||
#include "AP_Mount_MAVLink.h"
|
||||
#include "AP_Mount_Alexmos.h"
|
||||
#include "AP_Mount_SToRM32.h"
|
||||
#include "AP_Mount_SToRM32_serial.h"
|
||||
|
||||
const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
||||
// @Param: _DEFLT_MODE
|
||||
|
|
|
@ -22,11 +22,11 @@
|
|||
#ifndef __AP_MOUNT_H__
|
||||
#define __AP_MOUNT_H__
|
||||
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include "../RC_Channel/RC_Channel.h"
|
||||
#include "../AP_SerialManager/AP_SerialManager.h"
|
||||
|
||||
|
|
|
@ -7,13 +7,13 @@
|
|||
#ifndef __AP_MOUNT_ALEXMOS_H__
|
||||
#define __AP_MOUNT_ALEXMOS_H__
|
||||
|
||||
#include <AP_Mount.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_Mount_Backend.h>
|
||||
#include "AP_Mount.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include "AP_Mount_Backend.h"
|
||||
|
||||
|
||||
//definition of the commands id for the Alexmos Serial Protocol
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_Mount_Backend.h>
|
||||
#include "AP_Mount_Backend.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -22,8 +22,8 @@
|
|||
#ifndef __AP_MOUNT_BACKEND_H__
|
||||
#define __AP_MOUNT_BACKEND_H__
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Mount.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include "AP_Mount.h"
|
||||
|
||||
class AP_Mount_Backend
|
||||
{
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_Mount_MAVLink.h>
|
||||
#include "AP_Mount_MAVLink.h"
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <stdio.h>
|
||||
#include <AP_Gimbal.h>
|
||||
#include "AP_Gimbal.h"
|
||||
|
||||
#if MOUNT_DEBUG
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -7,17 +7,17 @@
|
|||
#ifndef __AP_MOUNT_MAVLINK_H__
|
||||
#define __AP_MOUNT_MAVLINK_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <RC_Channel.h>
|
||||
#include <AP_Mount_Backend.h>
|
||||
#include <AP_Gimbal.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include "AP_Mount_Backend.h"
|
||||
#include "AP_Gimbal.h"
|
||||
|
||||
class AP_Mount_MAVLink : public AP_Mount_Backend
|
||||
{
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_Mount_SToRM32.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include "AP_Mount_SToRM32.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -7,16 +7,16 @@
|
|||
#ifndef __AP_MOUNT_STORM32_H__
|
||||
#define __AP_MOUNT_STORM32_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <GCS.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <RC_Channel.h>
|
||||
#include <AP_Mount_Backend.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include "AP_Mount_Backend.h"
|
||||
|
||||
#define AP_MOUNT_STORM32_RESEND_MS 1000 // resend angle targets to gimbal once per second
|
||||
#define AP_MOUNT_STORM32_SEARCH_MS 60000 // search for gimbal for 1 minute after startup
|
||||
|
|
|
@ -1,9 +1,9 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_Mount_SToRM32_serial.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include "include/mavlink/v1.0/checksum.h"
|
||||
#include "AP_Mount_SToRM32_serial.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <GCS_MAVLink/include/mavlink/v1.0/checksum.h>
|
||||
#include "../AP_HAL/utility/RingBuffer.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
|
|
@ -7,15 +7,15 @@
|
|||
#ifndef __AP_MOUNT_STORM32_SERIAL_H__
|
||||
#define __AP_MOUNT_STORM32_SERIAL_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <RC_Channel.h>
|
||||
#include <AP_Mount_Backend.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include "AP_Mount_Backend.h"
|
||||
|
||||
#define AP_MOUNT_STORM32_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_Mount_Servo.h>
|
||||
#include "AP_Mount_Servo.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -7,12 +7,12 @@
|
|||
#ifndef __AP_MOUNT_SERVO_H__
|
||||
#define __AP_MOUNT_SERVO_H__
|
||||
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <RC_Channel_aux.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <RC_Channel/RC_Channel_aux.h>
|
||||
#include "AP_Mount_Backend.h"
|
||||
|
||||
class AP_Mount_Servo : public AP_Mount_Backend
|
||||
|
|
|
@ -1,35 +1,35 @@
|
|||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include <AP_GPS.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_InertialSensor.h>
|
||||
#include <AP_Compass.h>
|
||||
#include <AP_Declination.h>
|
||||
#include <AP_Airspeed.h>
|
||||
#include <AP_ADC.h>
|
||||
#include <AP_ADC_AnalogSource.h>
|
||||
#include <AP_Baro.h>
|
||||
#include <AP_Buffer.h>
|
||||
#include <Filter.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <AP_Mission.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_Terrain.h>
|
||||
#include <RC_Channel.h>
|
||||
#include <AP_Airspeed.h>
|
||||
#include <AP_Vehicle.h>
|
||||
#include <DataFlash.h>
|
||||
#include <AP_Notify.h>
|
||||
#include <AP_BattMonitor.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
#include <AP_Compass/AP_Compass.h>
|
||||
#include <AP_Declination/AP_Declination.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_ADC/AP_ADC.h>
|
||||
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
#include <AP_Buffer/AP_Buffer.h>
|
||||
#include <Filter/Filter.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_Mission/AP_Mission.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <DataFlash/DataFlash.h>
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||
|
||||
#include <AP_Mount.h>
|
||||
#include <AP_Mount/AP_Mount.h>
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
void setup () {
|
||||
|
|
Loading…
Reference in New Issue