2023-03-03 02:50:07 -04:00
|
|
|
/*
|
|
|
|
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 cameras that implement the newer MAVLink camera v2 protocol
|
|
|
|
see https://mavlink.io/en/services/camera.html
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "AP_Camera_Backend.h"
|
|
|
|
|
2023-04-04 03:36:54 -03:00
|
|
|
#if AP_CAMERA_MAVLINKCAMV2_ENABLED
|
2023-03-03 02:50:07 -04:00
|
|
|
|
|
|
|
class AP_Camera_MAVLinkCamV2 : public AP_Camera_Backend
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
|
|
|
|
// Constructor
|
|
|
|
using AP_Camera_Backend::AP_Camera_Backend;
|
|
|
|
|
|
|
|
/* Do not allow copies */
|
|
|
|
CLASS_NO_COPY(AP_Camera_MAVLinkCamV2);
|
|
|
|
|
|
|
|
// update - should be called at 50hz
|
|
|
|
void update() override;
|
|
|
|
|
|
|
|
// 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;
|
|
|
|
|
2023-04-06 21:49:46 -03:00
|
|
|
// set zoom specified as a rate or percentage
|
2023-04-18 22:06:16 -03:00
|
|
|
bool set_zoom(ZoomType zoom_type, float zoom_value) override;
|
2023-03-03 02:50:07 -04:00
|
|
|
|
2023-04-24 09:23:07 -03:00
|
|
|
// set focus specified as rate, percentage or auto
|
2023-03-03 02:50:07 -04:00
|
|
|
// focus in = -1, focus hold = 0, focus out = 1
|
2023-06-21 03:03:39 -03:00
|
|
|
SetFocusResult set_focus(FocusType focus_type, float focus_value) override;
|
2023-03-03 02:50:07 -04:00
|
|
|
|
2023-04-28 20:54:00 -03:00
|
|
|
// handle MAVLink messages from the camera
|
2023-03-03 02:50:07 -04:00
|
|
|
void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) override;
|
|
|
|
|
2023-06-09 23:17:12 -03:00
|
|
|
// send camera information message to GCS
|
|
|
|
void send_camera_information(mavlink_channel_t chan) const override;
|
|
|
|
|
2023-03-03 02:50:07 -04:00
|
|
|
private:
|
|
|
|
|
|
|
|
// search for camera in GCS_MAVLink routing table
|
|
|
|
void find_camera();
|
|
|
|
|
|
|
|
// request CAMERA_INFORMATION (holds vendor and model name)
|
|
|
|
void request_camera_information() const;
|
|
|
|
|
|
|
|
// internal members
|
|
|
|
bool _initialised; // true once the camera has provided a CAMERA_INFORMATION
|
|
|
|
bool _got_camera_info; // true once camera has provided CAMERA_INFORMATION
|
2023-06-09 23:17:12 -03:00
|
|
|
mavlink_camera_information_t _cam_info {}; // latest camera information received from camera
|
2023-03-03 02:50:07 -04:00
|
|
|
uint32_t _last_caminfo_req_ms; // system time that CAMERA_INFORMATION was last requested (used to throttle requests)
|
|
|
|
class GCS_MAVLINK *_link; // link we have found the camera on. nullptr if not seen yet
|
|
|
|
uint8_t _sysid; // sysid of camera
|
|
|
|
uint8_t _compid; // component id of gimbal
|
|
|
|
};
|
|
|
|
|
2023-04-04 03:36:54 -03:00
|
|
|
#endif // AP_CAMERA_MAVLINKCAMV2_ENABLED
|