AC_AttitudeControl: 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:
Gustavo Jose de Sousa 2015-08-11 16:28:41 +10:00 committed by Andrew Tridgell
parent 84b5555a1a
commit d49f10d2e5
8 changed files with 32 additions and 32 deletions

View File

@ -1,8 +1,8 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
#include "AC_AttitudeControl.h"
#include <AP_HAL.h>
#include <AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
// table of user settable parameters
const AP_Param::GroupInfo AC_AttitudeControl::var_info[] PROGMEM = {

View File

@ -6,14 +6,14 @@
#ifndef AC_AttitudeControl_H
#define AC_AttitudeControl_H
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <AP_InertialSensor.h>
#include <AP_AHRS.h>
#include <AP_Motors.h>
#include <AC_PID.h>
#include <AC_P.h>
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Motors/AP_Motors.h>
#include <AC_PID/AC_PID.h>
#include <AC_PID/AC_P.h>
// To-Do: change the name or move to AP_Math?
#define AC_ATTITUDE_CONTROL_DEGX100 5729.57795f // constant to convert from radians to centi-degrees

View File

@ -1,7 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
#include "AC_AttitudeControl_Heli.h"
#include <AP_HAL.h>
#include <AP_HAL/AP_HAL.h>
// table of user settable parameters
const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] PROGMEM = {

View File

@ -6,10 +6,10 @@
#ifndef AC_ATTITUDECONTROL_HELI_H
#define AC_ATTITUDECONTROL_HELI_H
#include <AC_AttitudeControl.h>
#include <AP_MotorsHeli.h>
#include <AC_HELI_PID.h>
#include <Filter.h>
#include "AC_AttitudeControl.h"
#include <AP_Motors/AP_MotorsHeli.h>
#include <AC_PID/AC_HELI_PID.h>
#include <Filter/Filter.h>
#define AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE 0.02f
#define AC_ATTITUDE_HELI_RATE_RP_FF_FILTER 10.0f

View File

@ -1,8 +1,8 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
#include "AC_AttitudeControl_Multi.h"
#include <AP_HAL.h>
#include <AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
// returns a throttle including compensation for roll/pitch angle
// throttle value should be 0 ~ 1000

View File

@ -6,8 +6,8 @@
#ifndef AC_AttitudeControl_Multi_H
#define AC_AttitudeControl_Multi_H
#include <AC_AttitudeControl.h>
#include <AP_MotorsMulticopter.h>
#include "AC_AttitudeControl.h"
#include <AP_Motors/AP_MotorsMulticopter.h>
class AC_AttitudeControl_Multi : public AC_AttitudeControl {
public:

View File

@ -1,7 +1,7 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#include <AC_PosControl.h>
#include <AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include "AC_PosControl.h"
#include <AP_Math/AP_Math.h>
extern const AP_HAL::HAL& hal;

View File

@ -2,16 +2,16 @@
#ifndef AC_POSCONTROL_H
#define AC_POSCONTROL_H
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <AC_PID.h> // PID library
#include <AC_PI_2D.h> // PID library (2-axis)
#include <AC_P.h> // P library
#include <AP_InertialNav.h> // Inertial Navigation library
#include <AC_AttitudeControl.h> // Attitude control library
#include <AP_Motors.h> // motors library
#include <AP_Vehicle.h> // common vehicle parameters
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AC_PID/AC_PID.h> // PID library
#include <AC_PID/AC_PI_2D.h> // PID library (2-axis)
#include <AC_PID/AC_P.h> // P library
#include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
#include "AC_AttitudeControl.h" // Attitude control library
#include <AP_Motors/AP_Motors.h> // motors library
#include <AP_Vehicle/AP_Vehicle.h> // common vehicle parameters
// position controller default definitions