Tracker: move many members up to base class

This commit is contained in:
Peter Barker 2018-12-27 17:35:49 +11:00 committed by Andrew Tridgell
parent 50b4e0b0c4
commit 29ba073f0c
1 changed files with 2 additions and 29 deletions

View File

@ -52,13 +52,9 @@
#include <AP_Terrain/AP_Terrain.h>
#include <AP_Rally/AP_Rally.h>
#include <AP_Stats/AP_Stats.h> // statistics library
#include <AP_Notify/AP_Notify.h> // Notify library
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_Beacon/AP_Beacon.h>
#include <AP_Common/AP_FWVersion.h>
@ -99,27 +95,14 @@ private:
// main loop scheduler
AP_Scheduler scheduler;
// notification object for LEDs, buzzers etc
AP_Notify notify;
uint32_t start_time_ms = 0;
AP_Logger logger;
AP_GPS gps;
AP_Baro barometer;
Compass compass;
AP_InertialSensor ins;
RangeFinder rng;
// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE
NavEKF2 EKF2{&ahrs, rng};
NavEKF3 EKF3{&ahrs, rng};
NavEKF2 EKF2{&ahrs, rangefinder};
NavEKF3 EKF3{&ahrs, rangefinder};
AP_AHRS_NavEKF ahrs{EKF2, EKF3};
#else
AP_AHRS_DCM ahrs;
@ -141,24 +124,15 @@ private:
bool yaw_servo_out_filt_init = false;
bool pitch_servo_out_filt_init = false;
AP_SerialManager serial_manager;
GCS_Tracker _gcs; // avoid using this; use gcs()
GCS_Tracker &gcs() { return _gcs; }
AP_Stats stats;
AP_BoardConfig BoardConfig;
#if HAL_WITH_UAVCAN
// board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN;
#endif
// Battery Sensors
AP_BattMonitor battery{MASK_LOG_CURRENT,
FUNCTOR_BIND_MEMBER(&Tracker::handle_battery_failsafe, void, const char*, const int8_t),
nullptr};
struct Location current_loc;
enum ControlMode control_mode = INITIALISING;
@ -297,5 +271,4 @@ public:
void mavlink_delay_cb();
};
extern const AP_HAL::HAL& hal;
extern Tracker tracker;