From 470b9638ea705a5a832d89b976c539743357f4a5 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 12 Apr 2023 20:11:08 +0900 Subject: [PATCH] AP_Mount: remove unused get_camera_state --- libraries/AP_Mount/AP_Mount.cpp | 9 --------- libraries/AP_Mount/AP_Mount.h | 1 - libraries/AP_Mount/AP_Mount_Backend.h | 1 - 3 files changed, 11 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index c52ecf96a9..93ef425ebb 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -565,15 +565,6 @@ void AP_Mount::set_attitude_euler(uint8_t instance, float roll_deg, float pitch_ backend->set_attitude_euler(roll_deg, pitch_deg, yaw_bf_deg); } -bool AP_Mount::get_camera_state(uint8_t instance, uint16_t& pic_count, bool& record_video, int8_t& zoom_step, int8_t& focus_step, bool& auto_focus) -{ - auto *backend = get_instance(instance); - if (backend == nullptr) { - return false; - } - return backend->get_camera_state(pic_count, record_video, zoom_step, focus_step, auto_focus); -} - // point at system ID sysid void AP_Mount::set_target_sysid(uint8_t instance, uint8_t sysid) { diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 1b97c29f14..e441eeca26 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -168,7 +168,6 @@ public: bool get_angle_target(uint8_t instance, float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame); bool get_location_target(uint8_t instance, Location& target_loc); void set_attitude_euler(uint8_t instance, float roll_deg, float pitch_deg, float yaw_bf_deg); - bool get_camera_state(uint8_t instance, uint16_t& pic_count, bool& record_video, int8_t& zoom_step, int8_t& focus_step, bool& auto_focus); // // camera controls for gimbals that include a camera diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index e62c0d8df3..7afd5545d8 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -112,7 +112,6 @@ public: virtual bool get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) { return false; } virtual bool get_location_target(Location &target_loc) { return false; } virtual void set_attitude_euler(float roll_deg, float pitch_deg, float yaw_bf_deg) {}; - virtual bool get_camera_state(uint16_t& pic_count, bool& record_video, int8_t& zoom_step, int8_t& focus_step, bool& auto_focus) { return false; } // // camera controls for gimbals that include a camera