AP_Camera: move ZoomType def to separate .h
This commit is contained in:
parent
a8c593d44c
commit
a1ae189b17
@ -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;
|
||||
|
@ -9,6 +9,7 @@
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#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
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
}
|
||||
|
@ -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
|
||||
|
@ -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) {
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
|
@ -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
|
||||
|
14
libraries/AP_Camera/AP_Camera_shareddefs.h
Normal file
14
libraries/AP_Camera/AP_Camera_shareddefs.h
Normal file
@ -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 <AP_Math/AP_Math.h>
|
||||
|
||||
// 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
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user