diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index dae4a72ff8..faa10e1774 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -33,9 +33,6 @@ #include #include #include -#include // ArduPilot GPS library -#include // ArduPilot barometer library -#include // ArduPilot Mega Magnetometer Library #include // ArduPilot Mega Vector/Matrix math Library #include // Inertial Sensor Library #include // interface and maths for accelerometer calibration @@ -43,7 +40,6 @@ #include #include // Range finder library #include // Filter library -#include // APM relay #include // Photo or video camera #include #include @@ -55,7 +51,6 @@ #include #include #include // MAVLink GCS definitions -#include // Serial manager library #include // Camera/Antenna mount #include // ArduPilot Mega Declination Helper Library #include @@ -74,23 +69,17 @@ #include // Mission command library #include -#include // Notify library #include // Battery monitor library #include -#include -#include #include #include -#include #include #include // Optical Flow library -#include // RSSI Library #include #include -#include #include #include #include @@ -189,42 +178,21 @@ private: // mapping between input channels RCMapper rcmap; - // board specific config - AP_BoardConfig BoardConfig; - - // board specific config for CAN bus -#if HAL_WITH_UAVCAN - AP_BoardConfig_CAN BoardConfig_CAN; -#endif - // primary input channels RC_Channel *channel_roll; RC_Channel *channel_pitch; RC_Channel *channel_throttle; RC_Channel *channel_rudder; - // notification object for LEDs, buzzers etc (parameter set to false disables external leds) - AP_Notify notify; - AP_Logger logger; // scaled roll limit based on pitch int32_t roll_limit_cd; int32_t pitch_limit_min_cd; - // Sensors - AP_GPS gps; - // flight modes convenience array AP_Int8 *flight_modes = &g.flight_mode1; - AP_Baro barometer; - Compass compass; - - AP_InertialSensor ins; - - RangeFinder rangefinder; - AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state; AP_RPM rpm_sensor; @@ -272,8 +240,6 @@ private: // external failsafe boards during baro and airspeed calibration bool in_calibration; - AP_SerialManager serial_manager; - // GCS selection GCS_Plane _gcs; // avoid using this; use gcs() GCS_Plane &gcs() { return _gcs; } @@ -284,12 +250,6 @@ private: // selected navigation controller AP_SpdHgtControl *SpdHgt_Controller = &TECS_controller; - // Relay - AP_Relay relay; - - // handle servo and relay events - AP_ServoRelayEvents ServoRelayEvents; - // Camera #if CAMERA == ENABLED AP_Camera camera{MASK_LOG_CAMERA, current_loc}; @@ -303,9 +263,6 @@ private: // Rally Ponints AP_Rally rally; - // RSSI - AP_RSSI rssi; - #if OSD_ENABLED == ENABLED AP_OSD osd; #endif @@ -1100,7 +1057,6 @@ public: void failsafe_check(void); }; -extern const AP_HAL::HAL& hal; extern Plane plane; using AP_HAL::millis;