From 14ef3870bc9ef097b704c6c3259de69058668ab7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 19 Apr 2023 10:06:46 +0900 Subject: [PATCH] AP_Mount: integrate ZoomType def move out of AP_Camera --- libraries/AP_Mission/AP_Mission_Commands.cpp | 4 ++-- libraries/AP_Mount/AP_Mount.cpp | 2 +- libraries/AP_Mount/AP_Mount.h | 4 ++-- libraries/AP_Mount/AP_Mount_Backend.h | 2 +- libraries/AP_Mount/AP_Mount_Siyi.cpp | 4 ++-- libraries/AP_Mount/AP_Mount_Siyi.h | 2 +- 6 files changed, 9 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Mission/AP_Mission_Commands.cpp b/libraries/AP_Mission/AP_Mission_Commands.cpp index 429491c87c..2c483b7b81 100644 --- a/libraries/AP_Mission/AP_Mission_Commands.cpp +++ b/libraries/AP_Mission/AP_Mission_Commands.cpp @@ -131,10 +131,10 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd) case MAV_CMD_SET_CAMERA_ZOOM: if (cmd.content.set_camera_zoom.zoom_type == ZOOM_TYPE_CONTINUOUS) { - return camera->set_zoom(AP_Camera::ZoomType::RATE, cmd.content.set_camera_zoom.zoom_value); + return camera->set_zoom(ZoomType::RATE, cmd.content.set_camera_zoom.zoom_value); } if (cmd.content.set_camera_zoom.zoom_type == ZOOM_TYPE_RANGE) { - return camera->set_zoom(AP_Camera::ZoomType::PCT, cmd.content.set_camera_zoom.zoom_value); + return camera->set_zoom(ZoomType::PCT, cmd.content.set_camera_zoom.zoom_value); } return false; diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index c4c8cd91dd..1693d08032 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -619,7 +619,7 @@ bool AP_Mount::record_video(uint8_t instance, bool start_recording) } // set zoom specified as a rate or percentage -bool AP_Mount::set_zoom(uint8_t instance, AP_Camera::ZoomType zoom_type, float zoom_value) +bool AP_Mount::set_zoom(uint8_t instance, ZoomType zoom_type, float zoom_value) { auto *backend = get_instance(instance); if (backend == nullptr) { diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index ff7524c5cd..30d0776307 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -27,7 +27,7 @@ #include #include #include -#include +#include #include "AP_Mount_Params.h" // maximum number of mounts @@ -182,7 +182,7 @@ public: bool record_video(uint8_t instance, bool start_recording); // set zoom specified as a rate or percentage - bool set_zoom(uint8_t instance, AP_Camera::ZoomType zoom_type, float zoom_value); + bool set_zoom(uint8_t instance, ZoomType zoom_type, float zoom_value); // set focus in, out or hold // focus in = -1, focus hold = 0, focus out = 1 diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index d91bae8dc9..8b954e90c7 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -125,7 +125,7 @@ public: virtual bool record_video(bool start_recording) { return false; } // set zoom specified as a rate or percentage - virtual bool set_zoom(AP_Camera::ZoomType zoom_type, float zoom_value) { return false; } + virtual bool set_zoom(ZoomType zoom_type, float zoom_value) { return false; } // set focus in, out or hold. returns true on success // focus in = -1, focus hold = 0, focus out = 1 diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index e90f9b9af0..781d190fd6 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -626,9 +626,9 @@ bool AP_Mount_Siyi::record_video(bool start_recording) } // set zoom specified as a rate or percentage -bool AP_Mount_Siyi::set_zoom(AP_Camera::ZoomType zoom_type, float zoom_value) +bool AP_Mount_Siyi::set_zoom(ZoomType zoom_type, float zoom_value) { - if (zoom_type == AP_Camera::ZoomType::RATE) { + if (zoom_type == ZoomType::RATE) { uint8_t zoom_step = 0; if (zoom_value > 0) { zoom_step = 1; diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index 6d000a36e7..7f2f21c6c9 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -63,7 +63,7 @@ public: bool record_video(bool start_recording) override; // set zoom specified as a rate or percentage - bool set_zoom(AP_Camera::ZoomType zoom_type, float zoom_value) override; + bool set_zoom(ZoomType zoom_type, float zoom_value) override; // set focus in, out or hold. returns true on success // focus in = -1, focus hold = 0, focus out = 1