Copter: move many members up to base class

This commit is contained in:
Peter Barker 2018-12-27 17:37:50 +11:00 committed by Andrew Tridgell
parent 29ba073f0c
commit e965e8f11e

View File

@ -35,11 +35,7 @@
// Application dependencies
#include <GCS_MAVLink/GCS.h>
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
#include <AP_Baro/AP_Baro.h>
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
@ -52,10 +48,7 @@
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
#include <AP_Motors/AP_Motors.h> // AP Motors library
#include <AP_Stats/AP_Stats.h> // statistics library
#include <AP_RSSI/AP_RSSI.h> // RSSI Library
#include <Filter/Filter.h> // Filter library
#include <AP_Relay/AP_Relay.h> // APM relay
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_Airspeed/AP_Airspeed.h> // needed for AHRS build
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
#include <AP_InertialNav/AP_InertialNav.h> // ArduPilot Mega inertial navigation library
@ -65,10 +58,7 @@
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
#include <AP_Notify/AP_Notify.h> // Notify library
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
#include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
#include <AC_InputManager/AC_InputManager_Heli.h> // 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;