mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: 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
99fd585a54
commit
ee2c388bb0
|
@ -1,7 +1,7 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#include <AP_HAL.h>
|
||||
#include <AC_Circle.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AC_Circle.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -2,11 +2,11 @@
|
|||
#ifndef AC_CIRCLE_H
|
||||
#define AC_CIRCLE_H
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_InertialNav.h> // Inertial Navigation library
|
||||
#include <AC_PosControl.h> // Position control library
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
|
||||
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
|
||||
|
||||
// loiter maximum velocities and accelerations
|
||||
#define AC_CIRCLE_RADIUS_DEFAULT 1000.0f // radius of the circle in cm that the vehicle will fly
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#include <AP_HAL.h>
|
||||
#include <AC_WPNav.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AC_WPNav.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -2,12 +2,12 @@
|
|||
#ifndef AC_WPNAV_H
|
||||
#define AC_WPNAV_H
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_InertialNav.h> // Inertial Navigation library
|
||||
#include <AC_PosControl.h> // Position control library
|
||||
#include <AC_AttitudeControl.h> // Attitude control library
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
|
||||
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
|
||||
#include <AC_AttitudeControl/AC_AttitudeControl.h> // Attitude control library
|
||||
|
||||
// loiter maximum velocities and accelerations
|
||||
#define WPNAV_ACCELERATION 100.0f // defines the default velocity vs distant curve. maximum acceleration in cm/s/s that position controller asks for from acceleration controller
|
||||
|
|
Loading…
Reference in New Issue