CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Camera/AP_Camera_Backend.h
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
/*
17
Camera driver backend class. Each supported camera type
18
needs to have an object derived from this class.
19
*/
20
#pragma once
21
22
#include "AP_Camera_config.h"
23
24
#if AP_CAMERA_ENABLED
25
#include "AP_Camera.h"
26
#include <AP_Common/Location.h>
27
#include <AP_Logger/LogStructure.h>
28
29
class AP_Camera_Backend
30
{
31
public:
32
33
// Constructor
34
AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params &params, uint8_t instance);
35
36
/* Do not allow copies */
37
CLASS_NO_COPY(AP_Camera_Backend);
38
39
// camera options parameter values
40
enum class Option : uint8_t {
41
RecordWhileArmed = (1 << 0U)
42
};
43
bool option_is_enabled(Option option) const {
44
return ((uint8_t)_params.options.get() & (uint8_t)option) != 0;
45
}
46
47
// init - performs any required initialisation
48
virtual void init();
49
50
// update - should be called at 50hz
51
virtual void update();
52
53
// return true if healthy
54
virtual bool healthy() const { return true; }
55
56
// momentary switch to change camera between picture and video modes
57
virtual void cam_mode_toggle() {}
58
59
// take a picture. returns true on success
60
bool take_picture();
61
62
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
63
// total_num is number of pictures to be taken, -1 means capture forever
64
void take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num);
65
66
// stop capturing multiple image sequence
67
void stop_capture();
68
69
// entry point to actually take a picture. returns true on success
70
virtual bool trigger_pic() = 0;
71
72
// start or stop video recording. returns true on success
73
// set start_recording = true to start record, false to stop recording
74
virtual bool record_video(bool start_recording) { return false; }
75
76
// set zoom specified as a rate or percentage
77
virtual bool set_zoom(ZoomType zoom_type, float zoom_value) { return false; }
78
79
// set focus specified as rate, percentage or auto
80
// focus in = -1, focus hold = 0, focus out = 1
81
virtual SetFocusResult set_focus(FocusType focus_type, float focus_value) { return SetFocusResult::UNSUPPORTED; }
82
83
// set tracking to none, point or rectangle (see TrackingType enum)
84
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
85
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
86
virtual bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) { return false; }
87
88
// set camera lens as a value from 0 to 5
89
virtual bool set_lens(uint8_t lens) { return false; }
90
91
#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
92
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
93
virtual bool set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) { return false; }
94
#endif
95
96
// get camera image horizontal or vertical field of view in degrees. returns 0 if unknown
97
float horizontal_fov() const { return MAX(0, _params.hfov); }
98
float vertical_fov() const { return MAX(0, _params.vfov); }
99
100
// handle MAVLink messages from the camera
101
virtual void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) {}
102
103
// configure camera
104
virtual void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) {}
105
106
// handle camera control
107
virtual void control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id);
108
109
// set camera trigger distance in meters
110
void set_trigger_distance(float distance_m) { _params.trigg_dist.set(distance_m); }
111
112
// send camera feedback message to GCS
113
void send_camera_feedback(mavlink_channel_t chan);
114
115
// send camera information message to GCS
116
virtual void send_camera_information(mavlink_channel_t chan) const;
117
118
#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
119
// send video stream information message to GCS
120
virtual void send_video_stream_information(mavlink_channel_t chan) const;
121
#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
122
123
#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
124
void set_camera_information(mavlink_camera_information_t camera_info);
125
void set_stream_information(mavlink_video_stream_information_t stream_info);
126
#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
127
128
// send camera settings message to GCS
129
virtual void send_camera_settings(mavlink_channel_t chan) const;
130
131
#if AP_CAMERA_SEND_FOV_STATUS_ENABLED
132
// send camera field of view status
133
void send_camera_fov_status(mavlink_channel_t chan) const;
134
#endif
135
136
// send camera capture status message to GCS
137
virtual void send_camera_capture_status(mavlink_channel_t chan) const;
138
139
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
140
// send camera thermal range message to GCS
141
virtual void send_camera_thermal_range(mavlink_channel_t chan) const {};
142
#endif
143
144
#if AP_CAMERA_SCRIPTING_ENABLED
145
// accessor to allow scripting backend to retrieve state
146
// returns true on success and cam_state is filled in
147
virtual bool get_state(AP_Camera::camera_state_t& cam_state) { return false; }
148
149
// change camera settings not normally used by autopilot
150
virtual bool change_setting(CameraSetting setting, float value) { return false; }
151
#endif
152
153
protected:
154
155
// references
156
AP_Camera &_frontend; // reference to the front end which holds parameters
157
AP_Camera_Params &_params; // parameters for this backend
158
159
// feedback pin related methods
160
void setup_feedback_callback();
161
void feedback_pin_isr(uint8_t pin, bool high, uint32_t timestamp_us);
162
void feedback_pin_timer();
163
void check_feedback();
164
165
// store vehicle location and attitude for use in camera_feedback message to GCS
166
void prep_mavlink_msg_camera_feedback(uint64_t timestamp_us);
167
struct {
168
uint64_t timestamp_us; // system time of most recent image
169
Location location; // location where most recent image was taken
170
int32_t roll_sensor; // vehicle roll in centi-degrees
171
int32_t pitch_sensor; // vehicle pitch in centi-degrees
172
int32_t yaw_sensor; // vehicle yaw in centi-degrees
173
uint32_t feedback_trigger_logged_count; // ID sequence number
174
} camera_feedback;
175
176
// Picture settings
177
struct {
178
uint32_t time_interval_ms; // time interval (in miliseconds) between two consecutive pictures
179
int16_t num_remaining; // number of pictures still to be taken, -1 means take unlimited pictures
180
} time_interval_settings;
181
182
// Logging Function
183
void log_picture();
184
void Write_Camera(uint64_t timestamp_us=0);
185
void Write_Trigger();
186
void Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us=0);
187
188
// get corresponding mount instance for the camera
189
uint8_t get_mount_instance() const;
190
191
// get mavlink gimbal device id which is normally mount_instance+1
192
uint8_t get_gimbal_device_id() const;
193
194
#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
195
mavlink_camera_information_t _camera_info;
196
mavlink_video_stream_information_t _stream_info;
197
#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
198
199
// internal members
200
uint8_t _instance; // this instance's number
201
bool timer_installed; // true if feedback pin change detected using timer
202
bool isr_installed; // true if feedback pin change is detected with an interrupt
203
uint8_t last_pin_state; // last pin state. used by timer based detection
204
uint32_t feedback_trigger_count; // number of times the interrupt detected the feedback pin changed
205
uint32_t feedback_trigger_timestamp_us; // system time (in microseconds) that timer detected the feedback pin changed
206
uint32_t feedback_trigger_logged_count; // number of times the feedback has been logged
207
bool trigger_pending; // true if a call to take_pic() was delayed due to the minimum time interval time
208
uint32_t last_picture_time_ms; // system time that photo was last taken
209
Location last_location; // Location that last picture was taken at (used for trigg_dist calculation)
210
uint16_t image_index; // number of pictures taken since boot
211
bool last_is_armed; // stores last arm/disarm state. true if it was armed lastly
212
};
213
214
#endif // AP_CAMERA_ENABLED
215
216