From 1aa75e4c3e87f44343bb596f15f4fcc8801178f4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 30 Aug 2018 21:02:09 +1000 Subject: [PATCH] Plane: use camera singleton to get camera rather than callback --- ArduPlane/GCS_Mavlink.cpp | 9 --------- ArduPlane/GCS_Mavlink.h | 1 - 2 files changed, 10 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index fd9869325a..d717a01950 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1610,15 +1610,6 @@ void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, mavlink_ } } -AP_Camera *GCS_MAVLINK_Plane::get_camera() const -{ -#if CAMERA == ENABLED - return &plane.camera; -#else - return nullptr; -#endif -} - AP_AdvancedFailsafe *GCS_MAVLINK_Plane::get_advanced_failsafe() const { return &plane.afs; diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 5180712708..6e92bd0c85 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -19,7 +19,6 @@ protected: AP_Mission *get_mission() override; void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg) override; - AP_Camera *get_camera() const override; AP_AdvancedFailsafe *get_advanced_failsafe() const override; AP_Rally *get_rally() const override;