mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Camera: add scripting backend
This commit is contained in:
parent
58b73c3613
commit
f357bc53fe
@ -17,6 +17,7 @@
|
||||
#include "AP_Camera_Mount.h"
|
||||
#include "AP_Camera_MAVLink.h"
|
||||
#include "AP_Camera_MAVLinkCamV2.h"
|
||||
#include "AP_Camera_Scripting.h"
|
||||
|
||||
const AP_Param::GroupInfo AP_Camera::var_info[] = {
|
||||
|
||||
@ -170,6 +171,12 @@ void AP_Camera::init()
|
||||
case CameraType::MAVLINK_CAMV2:
|
||||
_backends[instance] = new AP_Camera_MAVLinkCamV2(*this, _params[instance], instance);
|
||||
break;
|
||||
#endif
|
||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||
// check for Scripting driver
|
||||
case CameraType::SCRIPTING:
|
||||
_backends[instance] = new AP_Camera_Scripting(*this, _params[instance], instance);
|
||||
break;
|
||||
#endif
|
||||
case CameraType::NONE:
|
||||
break;
|
||||
@ -430,6 +437,19 @@ bool AP_Camera::set_auto_focus(uint8_t instance)
|
||||
return backend->set_auto_focus();
|
||||
}
|
||||
|
||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||
// accessor to allow scripting backend to retrieve state
|
||||
// returns true on success and cam_state is filled in
|
||||
bool AP_Camera::get_state(uint8_t instance, camera_state_t& cam_state) const
|
||||
{
|
||||
auto *backend = get_instance(instance);
|
||||
if (backend == nullptr) {
|
||||
return false;
|
||||
}
|
||||
return backend->get_state(cam_state);
|
||||
}
|
||||
#endif // #if AP_CAMERA_SCRIPTING_ENABLED
|
||||
|
||||
// return backend for instance number
|
||||
AP_Camera_Backend *AP_Camera::get_instance(uint8_t instance) const
|
||||
{
|
||||
|
@ -13,6 +13,17 @@
|
||||
#include "AP_Camera_Params.h"
|
||||
#include "AP_Mount/AP_Mount_config.h"
|
||||
|
||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||
// structure and accessors for use by scripting backends
|
||||
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
|
||||
int8_t focus_step; // focus in = -1, focus hold = 0, focus out = 1
|
||||
bool auto_focus; // true when auto focusing
|
||||
} camera_state_t;
|
||||
#endif
|
||||
|
||||
#define AP_CAMERA_MAX_INSTANCES 2 // maximum number of camera backends
|
||||
|
||||
// declare backend classes
|
||||
@ -23,6 +34,7 @@ class AP_Camera_SoloGimbal;
|
||||
class AP_Camera_Mount;
|
||||
class AP_Camera_MAVLink;
|
||||
class AP_Camera_MAVLinkCamV2;
|
||||
class AP_Camera_Scripting;
|
||||
|
||||
/// @class Camera
|
||||
/// @brief Object managing a Photo or video camera
|
||||
@ -36,6 +48,7 @@ class AP_Camera {
|
||||
friend class AP_Camera_Mount;
|
||||
friend class AP_Camera_MAVLink;
|
||||
friend class AP_Camera_MAVLinkCamV2;
|
||||
friend class AP_Camera_Scripting;
|
||||
|
||||
public:
|
||||
|
||||
@ -68,6 +81,9 @@ public:
|
||||
#endif
|
||||
#if AP_CAMERA_MAVLINKCAMV2_ENABLED
|
||||
MAVLINK_CAMV2 = 6, // MAVLink camera v2
|
||||
#endif
|
||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||
SCRIPTING = 7, // Scripting backend
|
||||
#endif
|
||||
};
|
||||
|
||||
@ -124,6 +140,12 @@ public:
|
||||
// set if vehicle is in AUTO mode
|
||||
void set_is_auto_mode(bool enable) { _is_in_auto_mode = enable; }
|
||||
|
||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||
// accessor to allow scripting backend to retrieve state
|
||||
// returns true on success and cam_state is filled in
|
||||
bool get_state(uint8_t instance, camera_state_t& cam_state) const;
|
||||
#endif
|
||||
|
||||
// parameter var table
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
@ -82,6 +82,12 @@ public:
|
||||
// send camera feedback message to GCS
|
||||
void send_camera_feedback(mavlink_channel_t chan) const;
|
||||
|
||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||
// accessor to allow scripting backend to retrieve state
|
||||
// returns true on success and cam_state is filled in
|
||||
virtual bool get_state(camera_state_t& cam_state) const { return false; }
|
||||
#endif
|
||||
|
||||
protected:
|
||||
|
||||
// references
|
||||
|
@ -8,7 +8,7 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = {
|
||||
// @Param: _TYPE
|
||||
// @DisplayName: Camera shutter (trigger) type
|
||||
// @Description: how to trigger the camera to take a picture
|
||||
// @Values: 1:Servo,2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi), 5:MAVLink, 6:MAVLinkCamV2
|
||||
// @Values: 1:Servo,2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi), 5:MAVLink, 6:MAVLinkCamV2, 7:Scripting
|
||||
// @User: Standard
|
||||
AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Camera_Params, type, 0, AP_PARAM_FLAG_ENABLE),
|
||||
|
||||
|
56
libraries/AP_Camera/AP_Camera_Scripting.cpp
Normal file
56
libraries/AP_Camera/AP_Camera_Scripting.cpp
Normal file
@ -0,0 +1,56 @@
|
||||
#include "AP_Camera_Scripting.h"
|
||||
|
||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// entry point to actually take a picture
|
||||
bool AP_Camera_Scripting::trigger_pic()
|
||||
{
|
||||
// increment counter to allow backend to notice request
|
||||
_cam_state.take_pic_incr++;
|
||||
return true;
|
||||
}
|
||||
|
||||
// start or stop video recording. returns true on success
|
||||
// set start_recording = true to start record, false to stop recording
|
||||
bool AP_Camera_Scripting::record_video(bool start_recording)
|
||||
{
|
||||
_cam_state.recording_video = 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)
|
||||
{
|
||||
_cam_state.zoom_step = zoom_step;
|
||||
return true;
|
||||
}
|
||||
|
||||
// set focus in, out or hold. returns true on success
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
bool AP_Camera_Scripting::set_manual_focus_step(int8_t focus_step)
|
||||
{
|
||||
_cam_state.focus_step = focus_step;
|
||||
_cam_state.auto_focus = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
// auto focus. returns true on success
|
||||
bool AP_Camera_Scripting::set_auto_focus()
|
||||
{
|
||||
_cam_state.auto_focus = true;
|
||||
_cam_state.focus_step = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
// access for scripting backend to retrieve state
|
||||
// returns true on success and cam_state is filled in
|
||||
bool AP_Camera_Scripting::get_state(camera_state_t& cam_state) const
|
||||
{
|
||||
cam_state = _cam_state;
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // AP_CAMERA_SCRIPTING_ENABLED
|
62
libraries/AP_Camera/AP_Camera_Scripting.h
Normal file
62
libraries/AP_Camera/AP_Camera_Scripting.h
Normal file
@ -0,0 +1,62 @@
|
||||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/*
|
||||
Camera driver for scripting backends
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_Camera_Backend.h"
|
||||
|
||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||
|
||||
class AP_Camera_Scripting : public AP_Camera_Backend
|
||||
{
|
||||
public:
|
||||
|
||||
// Constructor
|
||||
using AP_Camera_Backend::AP_Camera_Backend;
|
||||
|
||||
/* Do not allow copies */
|
||||
CLASS_NO_COPY(AP_Camera_Scripting);
|
||||
|
||||
// entry point to actually take a picture
|
||||
bool trigger_pic() override;
|
||||
|
||||
// start or stop video recording. returns true on success
|
||||
// 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 focus in, out or hold. returns true on success
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
bool set_manual_focus_step(int8_t focus_step) override;
|
||||
|
||||
// auto focus. returns true on success
|
||||
bool set_auto_focus() override;
|
||||
|
||||
// returns true on success and cam_state is filled in
|
||||
bool get_state(camera_state_t& cam_state) const override;
|
||||
|
||||
private:
|
||||
|
||||
// current state
|
||||
camera_state_t _cam_state;
|
||||
};
|
||||
|
||||
#endif // AP_CAMERA_SCRIPTING_ENABLED
|
@ -34,3 +34,7 @@
|
||||
#ifndef AP_CAMERA_SOLOGIMBAL_ENABLED
|
||||
#define AP_CAMERA_SOLOGIMBAL_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_SOLO_GIMBAL_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_CAMERA_SCRIPTING_ENABLED
|
||||
#define AP_CAMERA_SCRIPTING_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && AP_SCRIPTING_ENABLED
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user