AP_Math: remove unnecessary includes

Remove unnecessary includes, in particular the includes for specific
boards. The list of libraries for 'polygon' example was updated so that
the example compiles again.
This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-10-19 17:30:26 -02:00 committed by Andrew Tridgell
parent ef615a5da1
commit 5020db4481
5 changed files with 23 additions and 101 deletions

View File

@ -4,38 +4,7 @@
//
#include <AP_HAL/AP_HAL.h>
#include <stdlib.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.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_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_Math/AP_Math.h>
#include <Filter/Filter.h>
#include <AP_ADC/AP_ADC.h>
#include <SITL/SITL.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_GPS/AP_GPS.h>
#include <DataFlash/DataFlash.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission/AP_Mission.h>
#include <StorageManager/StorageManager.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_Declination/AP_Declination.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_Rally/AP_Rally.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();

View File

@ -3,39 +3,8 @@
// Unit tests for the AP_Math polygon code
//
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <Filter/Filter.h>
#include <AP_ADC/AP_ADC.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_GPS/AP_GPS.h>
#include <DataFlash/DataFlash.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 <AP_Declination/AP_Declination.h>
#include <AP_Rally/AP_Rally.h>
#include <AP_OpticalFlow/AP_OpticalFlow.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_AHRS/AP_AHRS.h>
#include <SITL/SITL.h>
#include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();

View File

@ -1,5 +1,26 @@
LIBRARIES += AP_ADC
LIBRARIES += AP_ADC_AnalogSource
LIBRARIES += AP_AHRS
LIBRARIES += AP_Airspeed
LIBRARIES += AP_Baro
LIBRARIES += AP_BattMonitor
LIBRARIES += AP_Common
LIBRARIES += AP_Compass
LIBRARIES += AP_Declination
LIBRARIES += AP_GPS
LIBRARIES += AP_InertialSensor
LIBRARIES += AP_Math
LIBRARIES += AP_Mission
LIBRARIES += AP_NavEKF
LIBRARIES += AP_Notify
LIBRARIES += AP_OpticalFlow
LIBRARIES += AP_Param
LIBRARIES += AP_Progmem
LIBRARIES += AP_Rally
LIBRARIES += AP_RangeFinder
LIBRARIES += AP_Terrain
LIBRARIES += AP_Vehicle
LIBRARIES += DataFlash
LIBRARIES += Filter
LIBRARIES += GCS_MAVLink
LIBRARIES += StorageManager

View File

@ -3,14 +3,8 @@
// Unit tests for the AP_Math polygon code
//
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_Math/AP_Math.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();

View File

@ -2,40 +2,9 @@
//
// Unit tests for the AP_Math rotations code
//
#include <AP_HAL/AP_HAL.h>
#include <stdlib.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.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_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_Math/AP_Math.h>
#include <Filter/Filter.h>
#include <AP_ADC/AP_ADC.h>
#include <SITL/SITL.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_GPS/AP_GPS.h>
#include <DataFlash/DataFlash.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission/AP_Mission.h>
#include <StorageManager/StorageManager.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
#include <AP_AHRS/AP_AHRS.h>
#include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_Rally/AP_Rally.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();