From e965e8f11e9b31d4a75d79a0d48d46a1193dde2a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 27 Dec 2018 17:37:50 +1100 Subject: [PATCH] Copter: move many members up to base class --- ArduCopter/Copter.h | 40 ---------------------------------------- 1 file changed, 40 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index e03706aad1..1adc23c618 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -35,11 +35,7 @@ // Application dependencies #include -#include // Serial manager library -#include // ArduPilot GPS library #include // ArduPilot Mega Flash Memory Library -#include -#include // ArduPilot Mega Magnetometer Library #include // ArduPilot Mega Vector/Matrix math Library #include // interface and maths for accelerometer calibration #include // ArduPilot Mega Inertial Sensor (accel & gyro) Library @@ -52,10 +48,7 @@ #include // Position control library #include // AP Motors library #include // statistics library -#include // RSSI Library #include // Filter library -#include // APM relay -#include #include // needed for AHRS build #include // needed for AHRS build #include // ArduPilot Mega inertial navigation library @@ -65,10 +58,7 @@ #include // ArduPilot Mega Declination Helper Library #include // main loop scheduler #include // RC input mapping library -#include // Notify library #include // Battery monitor library -#include // board configuration library -#include #include // Landing Gear library #include // Pilot input handling library #include // Heli specific pilot input handling library @@ -259,9 +249,6 @@ private: // main loop scheduler AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Copter::fast_loop, void)}; - // AP_Notify instance - AP_Notify notify; - // used to detect MAVLink acks from GCS to stop compassmot uint8_t command_ack_counter; @@ -273,17 +260,10 @@ private: AP_Logger logger; - AP_GPS gps; - // flight modes convenience array AP_Int8 *flight_modes; const uint8_t num_flight_modes = 6; - AP_Baro barometer; - Compass compass; - AP_InertialSensor ins; - - RangeFinder rangefinder; struct RangeFinderState { bool enabled:1; bool alt_healthy:1; // true if we can trust the altitude from the rangefinder @@ -352,8 +332,6 @@ private: uint32_t ekfYawReset_ms; int8_t ekf_primary_core; - AP_SerialManager serial_manager; - // GCS selection GCS_Copter _gcs; // avoid using this; use gcs() GCS_Copter &gcs() { return _gcs; } @@ -412,14 +390,6 @@ private: // intertial nav alt when we armed float arming_altitude_m; - // board specific config - AP_BoardConfig BoardConfig; - -#if HAL_WITH_UAVCAN - // board specific config for CAN bus - AP_BoardConfig_CAN BoardConfig_CAN; -#endif - // Failsafe struct { uint32_t last_heartbeat_ms; // the time when the last HEARTBEAT message arrived from a GCS - used for triggering gcs failsafe @@ -511,12 +481,6 @@ private: // Used to exit the roll and pitch auto trim function uint8_t auto_trim_counter; - // Reference to the relay object - AP_Relay relay; - - // handle repeated servo and relay events - AP_ServoRelayEvents ServoRelayEvents; - // Camera #if CAMERA == ENABLED AP_Camera camera{MASK_LOG_CAMERA, current_loc}; @@ -542,9 +506,6 @@ private: AP_Rally_Copter rally; #endif - // RSSI - AP_RSSI rssi; - // Crop Sprayer #if SPRAYER_ENABLED == ENABLED AC_Sprayer sprayer; @@ -987,7 +948,6 @@ public: void failsafe_check(); // failsafe.cpp }; -extern const AP_HAL::HAL& hal; extern Copter copter; using AP_HAL::millis;