diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 1a003f803e..e857be85b9 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -55,10 +55,8 @@ #include // Attitude control library #include // Position control library #include // AP Motors library -#include // Range finder library #include // Filter library #include // APM relay -#include #include // Camera/Antenna mount #include // needed for AHRS build #include // ArduPilot Mega inertial navigation library @@ -70,8 +68,6 @@ #include // loop perf monitoring #include // Notify library #include // Battery monitor library -#include // board configuration library -#include #include #include // Joystick/gamepad button function assignment #include // Leak detector @@ -156,9 +152,6 @@ private: // main loop scheduler AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Sub::fast_loop, void)}; - // AP_Notify instance - AP_Notify notify; - // primary input control channels RC_Channel *channel_roll; RC_Channel *channel_pitch; @@ -169,16 +162,10 @@ private: AP_Logger logger; - AP_GPS gps; - AP_LeakDetector leak_detector; TSYS01 celsius; - AP_Baro barometer; - Compass compass; - AP_InertialSensor ins; - RangeFinder rangefinder; struct { bool enabled:1; 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 uint32_t ekfYawReset_ms = 0; - AP_SerialManager serial_manager; - // GCS selection GCS_Sub _gcs; // avoid using this; use gcs() GCS_Sub &gcs() { return _gcs; } @@ -254,14 +239,6 @@ private: RCMapper rcmap; #endif - // 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_leak_warn_ms; // last time a leak warning was sent to gcs @@ -398,12 +375,6 @@ private: AC_Loiter loiter_nav; AC_Circle circle_nav; - // 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}; diff --git a/ArduSub/joystick.cpp b/ArduSub/joystick.cpp index 4449ec781c..e4e2e90b2f 100644 --- a/ArduSub/joystick.cpp +++ b/ArduSub/joystick.cpp @@ -139,10 +139,10 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t 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 - switch (get_button(button)->function(shift)) { + switch (get_button(_button)->function(shift)) { case JSButton::button_function_t::k_arm_toggle: if (motors.armed()) { 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 - switch (get_button(button)->function(shift)) { + switch (get_button(_button)->function(shift)) { case JSButton::button_function_t::k_relay_1_momentary: relay.off(0); break;