diff --git a/AntennaTracker/AntennaTracker.cpp b/AntennaTracker/AntennaTracker.cpp index a0926baadb..2a60457149 100644 --- a/AntennaTracker/AntennaTracker.cpp +++ b/AntennaTracker/AntennaTracker.cpp @@ -112,11 +112,6 @@ void Tracker::one_second_loop() } } -#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 -// needed for APM1 inertialsensor driver -AP_ADC_ADS7844 apm1_adc; -#endif - const AP_HAL::HAL& hal = AP_HAL::get_HAL(); Tracker::Tracker(void) diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index c8b1fdd93a..634c9e1a59 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -44,7 +44,6 @@ #include // ArduPilot Mega DCM Library #include // Filter library #include // APM FIFO Buffer -#include #include // MAVLink GCS definitions #include // Serial manager library diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index b221357930..ebc8162cf3 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -241,16 +241,4 @@ void Tracker::check_usb_mux(void) // the user has switched to/from the telemetry port usb_connected = usb_check; - -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 - // the APM2 has a MUX setup where the first serial port switches - // between USB and a TTL serial connection. When on USB we use - // SERIAL0_BAUD, but when connected as a TTL serial port we run it - // at SERIAL1_BAUD. - if (usb_connected) { - serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_Console, 0); - } else { - serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_MAVLink, 0); - } -#endif }