mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: integrate ZoomType def move out of AP_Camera
This commit is contained in:
parent
a1ae189b17
commit
14ef3870bc
|
@ -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;
|
||||
|
||||
|
|
|
@ -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) {
|
||||
|
|
|
@ -27,7 +27,7 @@
|
|||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Common/Location.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_Camera/AP_Camera.h>
|
||||
#include <AP_Camera/AP_Camera_shareddefs.h>
|
||||
#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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue