Sub: move many members up to base class

This commit is contained in:
Peter Barker 2018-12-27 17:38:01 +11:00 committed by Andrew Tridgell
parent 5d405896f8
commit c0052a5e71
2 changed files with 4 additions and 33 deletions

View File

@ -55,10 +55,8 @@
#include <AC_AttitudeControl/AC_AttitudeControl_Sub.h> // Attitude control library #include <AC_AttitudeControl/AC_AttitudeControl_Sub.h> // Attitude control library
#include <AC_AttitudeControl/AC_PosControl_Sub.h> // Position control library #include <AC_AttitudeControl/AC_PosControl_Sub.h> // Position control library
#include <AP_Motors/AP_Motors.h> // AP Motors library #include <AP_Motors/AP_Motors.h> // AP Motors library
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
#include <Filter/Filter.h> // Filter library #include <Filter/Filter.h> // Filter library
#include <AP_Relay/AP_Relay.h> // APM relay #include <AP_Relay/AP_Relay.h> // APM relay
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_Mount/AP_Mount.h> // Camera/Antenna mount #include <AP_Mount/AP_Mount.h> // Camera/Antenna mount
#include <AP_Vehicle/AP_Vehicle.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 #include <AP_InertialNav/AP_InertialNav.h> // ArduPilot Mega inertial navigation library
@ -70,8 +68,6 @@
#include <AP_Scheduler/PerfInfo.h> // loop perf monitoring #include <AP_Scheduler/PerfInfo.h> // loop perf monitoring
#include <AP_Notify/AP_Notify.h> // Notify library #include <AP_Notify/AP_Notify.h> // Notify library
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor 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_Terrain/AP_Terrain.h> #include <AP_Terrain/AP_Terrain.h>
#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment #include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
#include <AP_LeakDetector/AP_LeakDetector.h> // Leak detector #include <AP_LeakDetector/AP_LeakDetector.h> // Leak detector
@ -156,9 +152,6 @@ private:
// main loop scheduler // main loop scheduler
AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Sub::fast_loop, void)}; AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Sub::fast_loop, void)};
// AP_Notify instance
AP_Notify notify;
// primary input control channels // primary input control channels
RC_Channel *channel_roll; RC_Channel *channel_roll;
RC_Channel *channel_pitch; RC_Channel *channel_pitch;
@ -169,16 +162,10 @@ private:
AP_Logger logger; AP_Logger logger;
AP_GPS gps;
AP_LeakDetector leak_detector; AP_LeakDetector leak_detector;
TSYS01 celsius; TSYS01 celsius;
AP_Baro barometer;
Compass compass;
AP_InertialSensor ins;
RangeFinder rangefinder;
struct { struct {
bool enabled:1; bool enabled:1;
bool alt_healthy:1; // true if we can trust the altitude from the rangefinder bool alt_healthy:1; // true if we can trust the altitude from the rangefinder
@ -214,8 +201,6 @@ private:
// system time in milliseconds of last recorded yaw reset from ekf // system time in milliseconds of last recorded yaw reset from ekf
uint32_t ekfYawReset_ms = 0; uint32_t ekfYawReset_ms = 0;
AP_SerialManager serial_manager;
// GCS selection // GCS selection
GCS_Sub _gcs; // avoid using this; use gcs() GCS_Sub _gcs; // avoid using this; use gcs()
GCS_Sub &gcs() { return _gcs; } GCS_Sub &gcs() { return _gcs; }
@ -254,14 +239,6 @@ private:
RCMapper rcmap; RCMapper rcmap;
#endif #endif
// board specific config
AP_BoardConfig BoardConfig;
#if HAL_WITH_UAVCAN
// board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN;
#endif
// Failsafe // Failsafe
struct { struct {
uint32_t last_leak_warn_ms; // last time a leak warning was sent to gcs uint32_t last_leak_warn_ms; // last time a leak warning was sent to gcs
@ -398,12 +375,6 @@ private:
AC_Loiter loiter_nav; AC_Loiter loiter_nav;
AC_Circle circle_nav; AC_Circle circle_nav;
// Reference to the relay object
AP_Relay relay;
// handle repeated servo and relay events
AP_ServoRelayEvents ServoRelayEvents;
// Camera // Camera
#if CAMERA == ENABLED #if CAMERA == ENABLED
AP_Camera camera{MASK_LOG_CAMERA, current_loc}; AP_Camera camera{MASK_LOG_CAMERA, current_loc};

View File

@ -139,10 +139,10 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
z_last = z; z_last = z;
} }
void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held) void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
{ {
// Act based on the function assigned to this button // Act based on the function assigned to this button
switch (get_button(button)->function(shift)) { switch (get_button(_button)->function(shift)) {
case JSButton::button_function_t::k_arm_toggle: case JSButton::button_function_t::k_arm_toggle:
if (motors.armed()) { if (motors.armed()) {
arming.disarm(); arming.disarm();
@ -586,10 +586,10 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
} }
} }
void Sub::handle_jsbutton_release(uint8_t button, bool shift) { void Sub::handle_jsbutton_release(uint8_t _button, bool shift) {
// Act based on the function assigned to this button // Act based on the function assigned to this button
switch (get_button(button)->function(shift)) { switch (get_button(_button)->function(shift)) {
case JSButton::button_function_t::k_relay_1_momentary: case JSButton::button_function_t::k_relay_1_momentary:
relay.off(0); relay.off(0);
break; break;