AP_AHRS: 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:42 +10:00 committed by Randy Mackay
parent 6bddbc26de
commit 7b2facf717
6 changed files with 56 additions and 56 deletions

View File

@ -14,8 +14,8 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_AHRS.h>
#include <AP_HAL.h>
#include "AP_AHRS.h"
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL& hal;
#if AHRS_EKF_USE_ALWAYS

View File

@ -22,14 +22,14 @@
*
*/
#include <AP_Math.h>
#include <AP_Math/AP_Math.h>
#include <inttypes.h>
#include <AP_Compass.h>
#include <AP_Airspeed.h>
#include <AP_GPS.h>
#include <AP_InertialSensor.h>
#include <AP_Baro.h>
#include <AP_Param.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Param/AP_Param.h>
#include "../AP_OpticalFlow/AP_OpticalFlow.h"
@ -444,8 +444,8 @@ protected:
uint8_t _active_accel_instance;
};
#include <AP_AHRS_DCM.h>
#include <AP_AHRS_NavEKF.h>
#include "AP_AHRS_DCM.h"
#include "AP_AHRS_NavEKF.h"
#if AP_AHRS_NAVEKF_AVAILABLE
#define AP_AHRS_TYPE AP_AHRS_NavEKF

View File

@ -21,8 +21,8 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_AHRS.h>
#include <AP_HAL.h>
#include "AP_AHRS.h"
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL& hal;

View File

@ -18,9 +18,9 @@
* ArduPilot
*
*/
#include <AP_HAL.h>
#include <AP_AHRS.h>
#include <AP_Vehicle.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_AHRS.h"
#include <AP_Vehicle/AP_Vehicle.h>
#if AP_AHRS_NAVEKF_AVAILABLE

View File

@ -21,11 +21,11 @@
*
*/
#include <AP_HAL.h>
#include <AP_AHRS.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_AHRS.h"
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
#include <AP_NavEKF.h>
#include <AP_NavEKF/AP_NavEKF.h>
#define AP_AHRS_NAVEKF_AVAILABLE 1
#define AP_AHRS_NAVEKF_SETTLE_TIME_MS 20000 // time in milliseconds the ekf needs to settle after being started

View File

@ -4,44 +4,44 @@
// Simple test for the AP_AHRS interface
//
#include <AP_HAL.h>
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_Math.h>
#include <AP_Param.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Baro.h> // ArduPilot Mega Barometer Library
#include <AP_GPS.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Baro.h>
#include <GCS_MAVLink.h>
#include <AP_Mission.h>
#include <StorageManager.h>
#include <AP_Terrain.h>
#include <Filter.h>
#include <SITL.h>
#include <AP_Buffer.h>
#include <AP_Notify.h>
#include <AP_Vehicle.h>
#include <DataFlash.h>
#include <AP_NavEKF.h>
#include <AP_Rally.h>
#include <AP_Scheduler.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_ADC/AP_ADC.h>
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_Baro/AP_Baro.h> // ArduPilot Mega Barometer Library
#include <AP_GPS/AP_GPS.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_Declination/AP_Declination.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Baro/AP_Baro.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission/AP_Mission.h>
#include <StorageManager/StorageManager.h>
#include <AP_Terrain/AP_Terrain.h>
#include <Filter/Filter.h>
#include <SITL/SITL.h>
#include <AP_Buffer/AP_Buffer.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <DataFlash/DataFlash.h>
#include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Rally/AP_Rally.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_Empty.h>
#include <AP_HAL_Linux.h>
#include <AP_HAL_PX4.h>
#include <AP_BattMonitor.h>
#include <AP_SerialManager.h>
#include <RC_Channel.h>
#include <AP_RangeFinder.h>
#include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <RC_Channel/RC_Channel.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;