Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Camera/AP_Camera_Backend.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415/*16Camera driver backend class. Each supported camera type17needs to have an object derived from this class.18*/19#pragma once2021#include "AP_Camera_config.h"2223#if AP_CAMERA_ENABLED24#include "AP_Camera.h"25#include <AP_Common/Location.h>26#include <AP_Logger/LogStructure.h>2728class AP_Camera_Backend29{30public:3132// Constructor33AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params ¶ms, uint8_t instance);3435/* Do not allow copies */36CLASS_NO_COPY(AP_Camera_Backend);3738// camera options parameter values39enum class Option : uint8_t {40RecordWhileArmed = (1 << 0U)41};42bool option_is_enabled(Option option) const {43return ((uint8_t)_params.options.get() & (uint8_t)option) != 0;44}4546// init - performs any required initialisation47virtual void init();4849// update - should be called at 50hz50virtual void update();5152// return true if healthy53virtual bool healthy() const { return true; }5455// momentary switch to change camera between picture and video modes56virtual void cam_mode_toggle() {}5758// take a picture. returns true on success59bool take_picture();6061// take multiple pictures, time_interval between two consecutive pictures is in miliseconds62// total_num is number of pictures to be taken, -1 means capture forever63void take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num);6465// stop capturing multiple image sequence66void stop_capture();6768// entry point to actually take a picture. returns true on success69virtual bool trigger_pic() = 0;7071// start or stop video recording. returns true on success72// set start_recording = true to start record, false to stop recording73virtual bool record_video(bool start_recording) { return false; }7475// set zoom specified as a rate or percentage76virtual bool set_zoom(ZoomType zoom_type, float zoom_value) { return false; }7778// set focus specified as rate, percentage or auto79// focus in = -1, focus hold = 0, focus out = 180virtual SetFocusResult set_focus(FocusType focus_type, float focus_value) { return SetFocusResult::UNSUPPORTED; }8182// set tracking to none, point or rectangle (see TrackingType enum)83// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right84// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom85virtual bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) { return false; }8687// set camera lens as a value from 0 to 588virtual bool set_lens(uint8_t lens) { return false; }8990#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED91// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type92virtual bool set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) { return false; }93#endif9495// get camera image horizontal or vertical field of view in degrees. returns 0 if unknown96float horizontal_fov() const { return MAX(0, _params.hfov); }97float vertical_fov() const { return MAX(0, _params.vfov); }9899// handle MAVLink messages from the camera100virtual void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) {}101102// configure camera103virtual void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) {}104105// handle camera control106virtual void control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id);107108// set camera trigger distance in meters109void set_trigger_distance(float distance_m) { _params.trigg_dist.set(distance_m); }110111// send camera feedback message to GCS112void send_camera_feedback(mavlink_channel_t chan);113114// send camera information message to GCS115virtual void send_camera_information(mavlink_channel_t chan) const;116117#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED118// send video stream information message to GCS119virtual void send_video_stream_information(mavlink_channel_t chan) const;120#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED121122#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED123void set_camera_information(mavlink_camera_information_t camera_info);124void set_stream_information(mavlink_video_stream_information_t stream_info);125#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED126127// send camera settings message to GCS128virtual void send_camera_settings(mavlink_channel_t chan) const;129130#if AP_CAMERA_SEND_FOV_STATUS_ENABLED131// send camera field of view status132void send_camera_fov_status(mavlink_channel_t chan) const;133#endif134135// send camera capture status message to GCS136virtual void send_camera_capture_status(mavlink_channel_t chan) const;137138#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED139// send camera thermal range message to GCS140virtual void send_camera_thermal_range(mavlink_channel_t chan) const {};141#endif142143#if AP_CAMERA_SCRIPTING_ENABLED144// accessor to allow scripting backend to retrieve state145// returns true on success and cam_state is filled in146virtual bool get_state(AP_Camera::camera_state_t& cam_state) { return false; }147148// change camera settings not normally used by autopilot149virtual bool change_setting(CameraSetting setting, float value) { return false; }150#endif151152protected:153154// references155AP_Camera &_frontend; // reference to the front end which holds parameters156AP_Camera_Params &_params; // parameters for this backend157158// feedback pin related methods159void setup_feedback_callback();160void feedback_pin_isr(uint8_t pin, bool high, uint32_t timestamp_us);161void feedback_pin_timer();162void check_feedback();163164// store vehicle location and attitude for use in camera_feedback message to GCS165void prep_mavlink_msg_camera_feedback(uint64_t timestamp_us);166struct {167uint64_t timestamp_us; // system time of most recent image168Location location; // location where most recent image was taken169int32_t roll_sensor; // vehicle roll in centi-degrees170int32_t pitch_sensor; // vehicle pitch in centi-degrees171int32_t yaw_sensor; // vehicle yaw in centi-degrees172uint32_t feedback_trigger_logged_count; // ID sequence number173} camera_feedback;174175// Picture settings176struct {177uint32_t time_interval_ms; // time interval (in miliseconds) between two consecutive pictures178int16_t num_remaining; // number of pictures still to be taken, -1 means take unlimited pictures179} time_interval_settings;180181// Logging Function182void log_picture();183void Write_Camera(uint64_t timestamp_us=0);184void Write_Trigger();185void Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us=0);186187// get corresponding mount instance for the camera188uint8_t get_mount_instance() const;189190// get mavlink gimbal device id which is normally mount_instance+1191uint8_t get_gimbal_device_id() const;192193#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED194mavlink_camera_information_t _camera_info;195mavlink_video_stream_information_t _stream_info;196#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED197198// internal members199uint8_t _instance; // this instance's number200bool timer_installed; // true if feedback pin change detected using timer201bool isr_installed; // true if feedback pin change is detected with an interrupt202uint8_t last_pin_state; // last pin state. used by timer based detection203uint32_t feedback_trigger_count; // number of times the interrupt detected the feedback pin changed204uint32_t feedback_trigger_timestamp_us; // system time (in microseconds) that timer detected the feedback pin changed205uint32_t feedback_trigger_logged_count; // number of times the feedback has been logged206bool trigger_pending; // true if a call to take_pic() was delayed due to the minimum time interval time207uint32_t last_picture_time_ms; // system time that photo was last taken208Location last_location; // Location that last picture was taken at (used for trigg_dist calculation)209uint16_t image_index; // number of pictures taken since boot210bool last_is_armed; // stores last arm/disarm state. true if it was armed lastly211};212213#endif // AP_CAMERA_ENABLED214215216