mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: 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
8011579c5a
commit
f7fd9e3d99
|
@ -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 HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
|
@ -10,9 +10,9 @@
|
|||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF.h"
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Vehicle.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
|
|
|
@ -21,19 +21,19 @@
|
|||
#ifndef AP_NavEKF
|
||||
#define AP_NavEKF
|
||||
|
||||
#include <AP_Math.h>
|
||||
#include <AP_InertialSensor.h>
|
||||
#include <AP_Baro.h>
|
||||
#include <AP_Airspeed.h>
|
||||
#include <AP_Compass.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Nav_Common.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <AP_RangeFinder.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_Compass/AP_Compass.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include "AP_Nav_Common.h"
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
|
||||
// #define MATH_CHECK_INDEXES 1
|
||||
|
||||
#include <vectorN.h>
|
||||
#include <AP_Math/vectorN.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
#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 HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
|
@ -13,9 +13,9 @@
|
|||
#endif
|
||||
|
||||
#include "AP_SmallEKF.h"
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Vehicle.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
|
|
|
@ -21,17 +21,17 @@
|
|||
#ifndef AP_SmallEKF
|
||||
#define AP_SmallEKF
|
||||
|
||||
#include <AP_Math.h>
|
||||
#include <AP_InertialSensor.h>
|
||||
#include <AP_Baro.h>
|
||||
#include <AP_Airspeed.h>
|
||||
#include <AP_Compass.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Nav_Common.h>
|
||||
#include <AP_AHRS.h>
|
||||
#include <AP_NavEKF.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_Compass/AP_Compass.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include "AP_Nav_Common.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include "AP_NavEKF.h"
|
||||
|
||||
#include <vectorN.h>
|
||||
#include <AP_Math/vectorN.h>
|
||||
|
||||
class SmallEKF
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue