mirror of https://github.com/ArduPilot/ardupilot
Tracker: remove unused includes
This commit is contained in:
parent
0857cf49d5
commit
8c2c38c80a
|
@ -1,6 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AC_PID/AC_PID.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
||||
// Global parameter class.
|
||||
//
|
||||
|
|
|
@ -29,33 +29,19 @@
|
|||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
|
||||
#include <AP_Baro/AP_Baro.h> // ArduPilot barometer library
|
||||
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h> // Inertial Sensor Library
|
||||
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
|
||||
#include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library
|
||||
#include <Filter/Filter.h> // Filter library
|
||||
|
||||
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
|
||||
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AC_PID/AC_PID.h>
|
||||
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
|
||||
#include <AP_NavEKF2/AP_NavEKF2.h>
|
||||
#include <AP_NavEKF3/AP_NavEKF3.h>
|
||||
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_Mission/AP_Mission.h>
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <AP_Rally/AP_Rally.h>
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||
#include <AP_Beacon/AP_Beacon.h>
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
|
||||
// Configuration
|
||||
|
|
Loading…
Reference in New Issue