|
|
|
@ -23,54 +23,20 @@
@@ -23,54 +23,20 @@
|
|
|
|
|
// Libraries
|
|
|
|
|
#include <AP_Common/AP_Common.h> |
|
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
|
#include <AC_PID/AC_P.h> |
|
|
|
|
#include <AC_PID/AC_PID.h> |
|
|
|
|
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration |
|
|
|
|
#include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library |
|
|
|
|
#include <AP_Baro/AP_Baro.h> |
|
|
|
|
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library |
|
|
|
|
#include <AP_Beacon/AP_Beacon.h> |
|
|
|
|
#include <AP_Camera/AP_Camera.h> // Camera triggering |
|
|
|
|
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library |
|
|
|
|
#include <AP_Declination/AP_Declination.h> // Compass declination library |
|
|
|
|
#include <AP_InertialSensor/AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library |
|
|
|
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library |
|
|
|
|
#include <AP_Mission/AP_Mission.h> // Mission command library |
|
|
|
|
#include <AP_Mount/AP_Mount.h> // Camera/Antenna mount |
|
|
|
|
#include <AP_NavEKF2/AP_NavEKF2.h> |
|
|
|
|
#include <AP_NavEKF3/AP_NavEKF3.h> |
|
|
|
|
#include <AP_Navigation/AP_Navigation.h> |
|
|
|
|
#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library |
|
|
|
|
#include <AP_Param/AP_Param.h> |
|
|
|
|
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library |
|
|
|
|
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library |
|
|
|
|
#include <AP_RPM/AP_RPM.h> // RPM input library |
|
|
|
|
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler |
|
|
|
|
#include <AP_Stats/AP_Stats.h> // statistics library |
|
|
|
|
#include <AP_Terrain/AP_Terrain.h> |
|
|
|
|
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build |
|
|
|
|
#include <AP_WheelEncoder/AP_WheelEncoder.h> |
|
|
|
|
#include <AP_WheelEncoder/AP_WheelRateControl.h> |
|
|
|
|
#include <APM_Control/AR_AttitudeControl.h> |
|
|
|
|
#include <APM_Control/AR_PosControl.h> |
|
|
|
|
#include <AR_WPNav/AR_WPNav_OA.h> |
|
|
|
|
#include <AP_SmartRTL/AP_SmartRTL.h> |
|
|
|
|
#include <AP_Logger/AP_Logger.h> |
|
|
|
|
#include <Filter/AverageFilter.h> // Mode Filter from Filter library |
|
|
|
|
#include <Filter/Butter.h> // Filter library - butterworth filter |
|
|
|
|
#include <Filter/Filter.h> // Filter library |
|
|
|
|
#include <Filter/LowPassFilter.h> |
|
|
|
|
#include <Filter/ModeFilter.h> // Mode Filter from Filter library |
|
|
|
|
#include <AC_Fence/AC_Fence.h> |
|
|
|
|
#include <AP_Proximity/AP_Proximity.h> |
|
|
|
|
#include <AC_Avoidance/AC_Avoid.h> |
|
|
|
|
#include <AC_Avoidance/AP_OAPathPlanner.h> |
|
|
|
|
#include <AP_Follow/AP_Follow.h> |
|
|
|
|
#include <AP_OSD/AP_OSD.h> |
|
|
|
|
#include <AP_WindVane/AP_WindVane.h> |
|
|
|
|
#include <AR_Motors/AP_MotorsUGV.h> |
|
|
|
|
#include <AP_Torqeedo/AP_Torqeedo.h> |
|
|
|
|
#include <AP_AIS/AP_AIS.h> |
|
|
|
|
|
|
|
|
|
#if AP_SCRIPTING_ENABLED |
|
|
|
|
#include <AP_Scripting/AP_Scripting.h> |
|
|
|
|