From f005ee4a4ca9be1f50579e5e0bba1bcd0bf68b20 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 30 Aug 2018 21:01:58 +1000 Subject: [PATCH] Copter: use camera singleton to get camera rather than callback --- ArduCopter/GCS_Mavlink.cpp | 9 --------- ArduCopter/GCS_Mavlink.h | 1 - 2 files changed, 10 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 00a022d19f..66313774d3 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1555,15 +1555,6 @@ AP_Mission *GCS_MAVLINK_Copter::get_mission() #endif } -AP_Camera *GCS_MAVLINK_Copter::get_camera() const -{ -#if CAMERA == ENABLED - return &copter.camera; -#else - return nullptr; -#endif -} - AP_AdvancedFailsafe *GCS_MAVLINK_Copter::get_advanced_failsafe() const { #if ADVANCED_FAILSAFE == ENABLED diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 62cc2ad19a..a145eed672 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -18,7 +18,6 @@ protected: AP_Mission *get_mission() override; AP_Rally *get_rally() const override; - AP_Camera *get_camera() const override; MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override; AP_AdvancedFailsafe *get_advanced_failsafe() const override; AP_VisualOdom *get_visual_odom() const override;