diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 91df78b139..a502968cde 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -233,11 +233,11 @@ MAV_RESULT AP_Camera::handle_command_long(const mavlink_command_long_t &packet) return MAV_RESULT_ACCEPTED; case MAV_CMD_SET_CAMERA_ZOOM: if (is_equal(packet.param1, (float)ZOOM_TYPE_CONTINUOUS) && - set_zoom(AP_Camera::ZoomType::RATE, packet.param2)) { + set_zoom(ZoomType::RATE, packet.param2)) { return MAV_RESULT_ACCEPTED; } if (is_equal(packet.param1, (float)ZOOM_TYPE_RANGE) && - set_zoom(AP_Camera::ZoomType::PCT, packet.param2)) { + set_zoom(ZoomType::PCT, packet.param2)) { return MAV_RESULT_ACCEPTED; } return MAV_RESULT_UNSUPPORTED; diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 3c9c6ab06e..39026f62d4 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -9,6 +9,7 @@ #include #include #include "AP_Camera_Params.h" +#include "AP_Camera_shareddefs.h" #define AP_CAMERA_MAX_INSTANCES 2 // maximum number of camera backends @@ -110,11 +111,6 @@ public: bool record_video(uint8_t instance, bool start_recording); // set zoom specified as a rate or percentage - // enumerators match MAVLink CAMERA_ZOOM_TYPE - enum class ZoomType : uint8_t { - RATE = 1, // zoom in, out or hold (zoom out = -1, hold = 0, zoom in = 1). Same as ZOOM_TYPE_CONTINUOUS - PCT = 2 // zoom to a percentage (from 0 to 100) of the full range. Same as ZOOM_TYPE_RANGE - }; bool set_zoom(ZoomType zoom_type, float zoom_value); bool set_zoom(uint8_t instance, ZoomType zoom_type, float zoom_value); @@ -135,7 +131,7 @@ public: typedef struct { uint16_t take_pic_incr; // incremented each time camera is requested to take a picture bool recording_video; // true when recording video - uint8_t zoom_type; // see AP_Camera::ZoomType enum (1:Rate or 2:Pct) + uint8_t zoom_type; // see ZoomType enum (1:Rate or 2:Pct) float zoom_value; // percentage or zoom out = -1, hold = 0, zoom in = 1 int8_t focus_step; // focus in = -1, focus hold = 0, focus out = 1 bool auto_focus; // true when auto focusing diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index adecd98d0a..ed62fa4ecb 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -59,7 +59,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_Camera/AP_Camera_MAVLinkCamV2.cpp b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp index 69072180cf..107db82ea5 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp +++ b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp @@ -65,7 +65,7 @@ bool AP_Camera_MAVLinkCamV2::record_video(bool start_recording) } // set zoom specified as a rate or percentage -bool AP_Camera_MAVLinkCamV2::set_zoom(AP_Camera::ZoomType zoom_type, float zoom_value) +bool AP_Camera_MAVLinkCamV2::set_zoom(ZoomType zoom_type, float zoom_value) { // exit immediately if have not found camera or does not support zoom if (_link == nullptr || !(_cap_flags & CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM)) { @@ -76,10 +76,10 @@ bool AP_Camera_MAVLinkCamV2::set_zoom(AP_Camera::ZoomType zoom_type, float zoom_ mavlink_command_long_t pkt {}; pkt.command = MAV_CMD_SET_CAMERA_ZOOM; switch (zoom_type) { - case AP_Camera::ZoomType::RATE: + case ZoomType::RATE: pkt.param1 = ZOOM_TYPE_CONTINUOUS; break; - case AP_Camera::ZoomType::PCT: + case ZoomType::PCT: pkt.param1 = ZOOM_TYPE_RANGE; break; } diff --git a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h index 412e36e101..582a602ca5 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h +++ b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h @@ -44,7 +44,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 diff --git a/libraries/AP_Camera/AP_Camera_Mount.cpp b/libraries/AP_Camera/AP_Camera_Mount.cpp index ca35390d73..4c61af0c3c 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.cpp +++ b/libraries/AP_Camera/AP_Camera_Mount.cpp @@ -28,7 +28,7 @@ bool AP_Camera_Mount::record_video(bool start_recording) } // set zoom specified as a rate or percentage -bool AP_Camera_Mount::set_zoom(AP_Camera::ZoomType zoom_type, float zoom_value) +bool AP_Camera_Mount::set_zoom(ZoomType zoom_type, float zoom_value) { AP_Mount* mount = AP::mount(); if (mount != nullptr) { diff --git a/libraries/AP_Camera/AP_Camera_Mount.h b/libraries/AP_Camera/AP_Camera_Mount.h index f2701f484d..752976e1b3 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.h +++ b/libraries/AP_Camera/AP_Camera_Mount.h @@ -40,7 +40,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 diff --git a/libraries/AP_Camera/AP_Camera_Scripting.cpp b/libraries/AP_Camera/AP_Camera_Scripting.cpp index c082b9dbd2..dd13722ec5 100644 --- a/libraries/AP_Camera/AP_Camera_Scripting.cpp +++ b/libraries/AP_Camera/AP_Camera_Scripting.cpp @@ -21,7 +21,7 @@ bool AP_Camera_Scripting::record_video(bool start_recording) } // set zoom specified as a rate or percentage -bool AP_Camera_Scripting::set_zoom(AP_Camera::ZoomType zoom_type, float zoom_value) +bool AP_Camera_Scripting::set_zoom(ZoomType zoom_type, float zoom_value) { _cam_state.zoom_type = (uint8_t)zoom_type; _cam_state.zoom_value = zoom_value; diff --git a/libraries/AP_Camera/AP_Camera_Scripting.h b/libraries/AP_Camera/AP_Camera_Scripting.h index 9bc7fae09e..3cfe616b01 100644 --- a/libraries/AP_Camera/AP_Camera_Scripting.h +++ b/libraries/AP_Camera/AP_Camera_Scripting.h @@ -40,7 +40,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 diff --git a/libraries/AP_Camera/AP_Camera_shareddefs.h b/libraries/AP_Camera/AP_Camera_shareddefs.h new file mode 100644 index 0000000000..fc428dfd21 --- /dev/null +++ b/libraries/AP_Camera/AP_Camera_shareddefs.h @@ -0,0 +1,14 @@ +#pragma once + +// Camera related definitions required by both AP_Camera and AP_Mount are here +// this avoids issues that would occur if AP_Mount and AP_Camera included each other + +#include + +// set zoom specified as a rate or percentage +// enumerators match MAVLink CAMERA_ZOOM_TYPE +enum class ZoomType : uint8_t { + RATE = 1, // zoom in, out or hold (zoom out = -1, hold = 0, zoom in = 1). Same as ZOOM_TYPE_CONTINUOUS + PCT = 2 // zoom to a percentage (from 0 to 100) of the full range. Same as ZOOM_TYPE_RANGE +}; +