AP_Camera: set_zoom replaces set_zoom_step

This commit is contained in:
Randy Mackay 2023-04-07 09:49:46 +09:00 committed by Andrew Tridgell
parent b1c4cf9923
commit 6603a6c8c5
9 changed files with 56 additions and 48 deletions

View File

@ -103,18 +103,6 @@ bool AP_Camera::record_video(bool start_recording)
return primary->record_video(start_recording);
}
// zoom in, out or hold
// zoom out = -1, hold = 0, zoom in = 1
bool AP_Camera::set_zoom_step(int8_t zoom_step)
{
WITH_SEMAPHORE(_rsem);
if (primary == nullptr) {
return false;
}
return primary->set_zoom_step(zoom_step);
}
// focus in, out or hold
// focus in = -1, focus hold = 0, focus out = 1
bool AP_Camera::set_manual_focus_step(int8_t focus_step)
@ -248,8 +236,12 @@ 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_step((int8_t)packet.param2);
if (is_equal(packet.param1, (float)ZOOM_TYPE_CONTINUOUS) &&
set_zoom(AP_Camera::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)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_UNSUPPORTED;
@ -435,9 +427,19 @@ bool AP_Camera::record_video(uint8_t instance, bool start_recording)
return backend->record_video(start_recording);
}
// zoom in, out or hold. returns true on success
// zoom out = -1, hold = 0, zoom in = 1
bool AP_Camera::set_zoom_step(uint8_t instance, int8_t zoom_step)
// zoom specified as a rate or percentage
bool AP_Camera::set_zoom(ZoomType zoom_type, float zoom_value)
{
WITH_SEMAPHORE(_rsem);
if (primary == nullptr) {
return false;
}
return primary->set_zoom(zoom_type, zoom_value);
}
// zoom specified as a rate or percentage
bool AP_Camera::set_zoom(uint8_t instance, ZoomType zoom_type, float zoom_value)
{
WITH_SEMAPHORE(_rsem);
@ -447,7 +449,7 @@ bool AP_Camera::set_zoom_step(uint8_t instance, int8_t zoom_step)
}
// call each instance
return backend->set_zoom_step(zoom_step);
return backend->set_zoom(zoom_type, zoom_value);
}
// focus in, out or hold. returns true on success

View File

@ -18,7 +18,8 @@
typedef struct {
uint16_t take_pic_incr; // incremented each time camera is requested to take a picture
bool recording_video; // true when recording video
int8_t zoom_step; // zoom out = -1, hold = 0, zoom in = 1
uint8_t zoom_type; // zoom AP_Camera::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
} camera_state_t;
@ -123,10 +124,14 @@ public:
bool record_video(bool start_recording);
bool record_video(uint8_t instance, bool start_recording);
// zoom in, out or hold
// zoom out = -1, hold = 0, zoom in = 1
bool set_zoom_step(int8_t zoom_step);
bool set_zoom_step(uint8_t instance, int8_t zoom_step);
// 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);
// focus in, out or hold
// focus in = -1, focus hold = 0, focus out = 1

View File

@ -56,9 +56,8 @@ public:
// set start_recording = true to start record, false to stop recording
virtual bool record_video(bool start_recording) { return false; }
// set camera zoom step. returns true on success
// zoom out = -1, hold = 0, zoom in = 1
virtual bool set_zoom_step(int8_t zoom_step) { return false; }
// set zoom specified as a rate or percentage
virtual bool set_zoom(AP_Camera::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

View File

@ -64,9 +64,8 @@ bool AP_Camera_MAVLinkCamV2::record_video(bool start_recording)
return true;
}
// set camera zoom step. returns true on success
// zoom out = -1, hold = 0, zoom in = 1
bool AP_Camera_MAVLinkCamV2::set_zoom_step(int8_t zoom_step)
// set zoom specified as a rate or percentage
bool AP_Camera_MAVLinkCamV2::set_zoom(AP_Camera::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,8 +75,15 @@ bool AP_Camera_MAVLinkCamV2::set_zoom_step(int8_t zoom_step)
// prepare and send message
mavlink_command_long_t pkt {};
pkt.command = MAV_CMD_SET_CAMERA_ZOOM;
pkt.param1 = ZOOM_TYPE_CONTINUOUS; // Zoom Type, 0:ZOOM_TYPE_STEP, 1:ZOOM_TYPE_CONTINUOUS, 2:ZOOM_TYPE_RANGE, 3:ZOOM_TYPE_FOCAL_LENGTH
pkt.param2 = zoom_step; // Zoom Value
switch (zoom_type) {
case AP_Camera::ZoomType::RATE:
pkt.param1 = ZOOM_TYPE_CONTINUOUS;
break;
case AP_Camera::ZoomType::PCT:
pkt.param1 = ZOOM_TYPE_RANGE;
break;
}
pkt.param2 = zoom_value; // Zoom Value
_link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt);

View File

@ -43,9 +43,8 @@ public:
// set start_recording = true to start record, false to stop recording
bool record_video(bool start_recording) override;
// set camera zoom step. returns true on success
// zoom out = -1, hold = 0, zoom in = 1
bool set_zoom_step(int8_t zoom_step) override;
// set zoom specified as a rate or percentage
bool set_zoom(AP_Camera::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

View File

@ -27,13 +27,12 @@ bool AP_Camera_Mount::record_video(bool start_recording)
return false;
}
// zoom in, out or hold. returns true on success
// zoom out = -1, hold = 0, zoom in = 1
bool AP_Camera_Mount::set_zoom_step(int8_t zoom_step)
// set zoom specified as a rate or percentage
bool AP_Camera_Mount::set_zoom(AP_Camera::ZoomType zoom_type, float zoom_value)
{
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
return mount->set_zoom_step(0, zoom_step);
return mount->set_zoom(0, zoom_type, zoom_value);
}
return false;
}

View File

@ -39,9 +39,8 @@ public:
// set start_recording = true to start record, false to stop recording
bool record_video(bool start_recording) override;
// set camera zoom step. returns true on success
// zoom out = -1, hold = 0, zoom in = 1
bool set_zoom_step(int8_t zoom_step) override;
// set zoom specified as a rate or percentage
bool set_zoom(AP_Camera::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

View File

@ -20,11 +20,11 @@ bool AP_Camera_Scripting::record_video(bool start_recording)
return true;
}
// set camera zoom step. returns true on success
// zoom out = -1, hold = 0, zoom in = 1
bool AP_Camera_Scripting::set_zoom_step(int8_t zoom_step)
// set zoom specified as a rate or percentage
bool AP_Camera_Scripting::set_zoom(AP_Camera::ZoomType zoom_type, float zoom_value)
{
_cam_state.zoom_step = zoom_step;
_cam_state.zoom_type = (uint8_t)zoom_type;
_cam_state.zoom_value = zoom_value;
return true;
}

View File

@ -39,9 +39,8 @@ public:
// set start_recording = true to start record, false to stop recording
bool record_video(bool start_recording) override;
// set camera zoom step. returns true on success
// zoom out = -1, hold = 0, zoom in = 1
bool set_zoom_step(int8_t zoom_step) override;
// set zoom specified as a rate or percentage
bool set_zoom(AP_Camera::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