diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 0a079cd0a8..fef860252b 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -37,7 +37,6 @@ #include // Camera triggering #include // ArduPilot Mega Magnetometer Library #include // Compass declination library -#include #include // ArduPilot GPS library #include // Inertial Sensor (uncalibated IMU) Library #include @@ -298,10 +297,6 @@ private: FUNCTOR_BIND_MEMBER(&Rover::handle_battery_failsafe, void, const char*, const int8_t), _failsafe_priorities}; -#if DEVO_TELEM_ENABLED == ENABLED - AP_DEVO_Telem devo_telemetry; -#endif - // 3D Location vectors // Location structure defined in AP_Common // The home location used for RTL. The location is set when we first get stable GPS lock diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index b6d3a3a379..14deb1a3b9 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -80,10 +80,6 @@ void Rover::init_ardupilot() // setup telem slots with serial ports gcs().setup_uarts(serial_manager); -#if DEVO_TELEM_ENABLED == ENABLED - devo_telemetry.init(); -#endif - #if OSD_ENABLED == ENABLED osd.init(); #endif @@ -256,10 +252,6 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason) // but it should be harmless to disable the fence temporarily in these situations as well g2.fence.manual_recovery_start(); -#if DEVO_TELEM_ENABLED == ENABLED - devo_telemetry.update_control_mode(control_mode->mode_number()); -#endif - #if CAMERA == ENABLED camera.set_is_auto_mode(control_mode->mode_number() == Mode::Number::AUTO); #endif