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.cpp
Views: 1798
1
#include "AP_Camera_config.h"
2
3
#if AP_CAMERA_ENABLED
4
5
#include "AP_Camera_Backend.h"
6
7
#include <GCS_MAVLink/GCS.h>
8
#include <AP_GPS/AP_GPS.h>
9
#include <AP_Mount/AP_Mount.h>
10
#include <AP_AHRS/AP_AHRS.h>
11
12
extern const AP_HAL::HAL& hal;
13
14
// Constructor
15
AP_Camera_Backend::AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params &params, uint8_t instance) :
16
_frontend(frontend),
17
_params(params),
18
_instance(instance)
19
{}
20
21
void AP_Camera_Backend::init()
22
{
23
#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
24
_camera_info.focal_length = NaNf;
25
_camera_info.sensor_size_h = NaNf;
26
_camera_info.sensor_size_v = NaNf;
27
28
_camera_info.flags = CAMERA_CAP_FLAGS_CAPTURE_IMAGE;
29
#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
30
}
31
32
// update - should be called at 50hz
33
void AP_Camera_Backend::update()
34
{
35
// Check camera options and start/stop recording based on arm/disarm
36
if (option_is_enabled(Option::RecordWhileArmed)) {
37
if (hal.util->get_soft_armed() != last_is_armed) {
38
last_is_armed = hal.util->get_soft_armed();
39
if (!record_video(last_is_armed)) {
40
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Camera: failed to %s recording", last_is_armed ? "start" : "stop");
41
}
42
}
43
}
44
45
// try to take picture if pending
46
if (trigger_pending) {
47
take_picture();
48
}
49
50
// check feedback pin
51
check_feedback();
52
53
// time based triggering
54
// if time and distance triggering both are enabled then we only do time based triggering
55
if (time_interval_settings.num_remaining != 0) {
56
uint32_t delta_ms = AP_HAL::millis() - last_picture_time_ms;
57
if (delta_ms > time_interval_settings.time_interval_ms) {
58
if (take_picture()) {
59
// decrease num_remaining except when its -1 i.e. capture forever
60
if (time_interval_settings.num_remaining > 0) {
61
time_interval_settings.num_remaining--;
62
}
63
}
64
}
65
return;
66
}
67
68
// implement trigger distance
69
if (!is_positive(_params.trigg_dist)) {
70
last_location.lat = 0;
71
last_location.lng = 0;
72
return;
73
}
74
75
const AP_AHRS &ahrs = AP::ahrs();
76
77
Location current_loc;
78
if (!ahrs.get_location(current_loc)) {
79
return;
80
}
81
82
// check vehicle flight mode supports trigg dist
83
if (!_frontend.vehicle_mode_ok_for_trigg_dist()) {
84
return;
85
}
86
87
// check vehicle roll angle is less than configured maximum
88
if ((_frontend.get_roll_max() > 0) && (fabsf(ahrs.roll_sensor * 1e-2f) > _frontend.get_roll_max())) {
89
return;
90
}
91
92
// initialise last location to current location
93
if (last_location.lat == 0 && last_location.lng == 0) {
94
last_location = current_loc;
95
return;
96
}
97
if (last_location.lat == current_loc.lat && last_location.lng == current_loc.lng) {
98
// we haven't moved - this can happen as update() may
99
// be called without a new GPS fix
100
return;
101
}
102
103
// check vehicle has moved at least trigg_dist meters
104
if (current_loc.get_distance(last_location) < _params.trigg_dist) {
105
return;
106
}
107
108
take_picture();
109
}
110
111
// get corresponding mount instance for the camera
112
uint8_t AP_Camera_Backend::get_mount_instance() const
113
{
114
// instance 0 means default
115
if (_params.mount_instance.get() == 0) {
116
return _instance;
117
}
118
return _params.mount_instance.get() - 1;
119
}
120
121
// get mavlink gimbal device id which is normally mount_instance+1
122
uint8_t AP_Camera_Backend::get_gimbal_device_id() const
123
{
124
#if HAL_MOUNT_ENABLED
125
const uint8_t mount_instance = get_mount_instance();
126
AP_Mount* mount = AP::mount();
127
if (mount != nullptr) {
128
if (mount->get_mount_type(mount_instance) != AP_Mount::Type::None) {
129
return (mount_instance + 1);
130
}
131
}
132
#endif
133
return 0;
134
}
135
136
137
// take a picture. returns true on success
138
bool AP_Camera_Backend::take_picture()
139
{
140
// setup feedback pin interrupt or timer
141
setup_feedback_callback();
142
143
// check minimum time interval since last picture taken
144
uint32_t now_ms = AP_HAL::millis();
145
if (now_ms - last_picture_time_ms < (uint32_t)(_params.interval_min * 1000)) {
146
trigger_pending = true;
147
return false;
148
}
149
150
trigger_pending = false;
151
152
// trigger actually taking picture and update image count
153
if (trigger_pic()) {
154
image_index++;
155
last_picture_time_ms = now_ms;
156
IGNORE_RETURN(AP::ahrs().get_location(last_location));
157
#if HAL_LOGGING_ENABLED
158
log_picture();
159
#endif
160
return true;
161
}
162
163
return false;
164
}
165
166
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
167
// total_num is number of pictures to be taken, -1 means capture forever
168
void AP_Camera_Backend::take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num)
169
{
170
time_interval_settings = {time_interval_ms, total_num};
171
}
172
173
// stop capturing multiple image sequence
174
void AP_Camera_Backend::stop_capture()
175
{
176
time_interval_settings = {0, 0};
177
}
178
179
// handle camera control
180
void AP_Camera_Backend::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)
181
{
182
// take picture
183
if (shooting_cmd == 1) {
184
take_picture();
185
}
186
}
187
188
// send camera feedback message to GCS
189
void AP_Camera_Backend::send_camera_feedback(mavlink_channel_t chan)
190
{
191
int32_t altitude = 0;
192
if (camera_feedback.location.initialised() && !camera_feedback.location.get_alt_cm(Location::AltFrame::ABSOLUTE, altitude)) {
193
// completely ignore this failure! this is a shouldn't-happen
194
// as current_loc should never be in an altitude we can't
195
// convert.
196
}
197
int32_t altitude_rel = 0;
198
if (camera_feedback.location.initialised() && !camera_feedback.location.get_alt_cm(Location::AltFrame::ABOVE_HOME, altitude_rel)) {
199
// completely ignore this failure! this is a shouldn't-happen
200
// as current_loc should never be in an altitude we can't
201
// convert.
202
}
203
204
// send camera feedback message
205
mavlink_msg_camera_feedback_send(
206
chan,
207
camera_feedback.timestamp_us, // image timestamp
208
0, // target system id
209
_instance, // camera id
210
image_index, // image index
211
camera_feedback.location.lat, // latitude
212
camera_feedback.location.lng, // longitude
213
altitude*1e-2f, // alt MSL
214
altitude_rel*1e-2f, // alt relative to home
215
camera_feedback.roll_sensor*1e-2f, // roll angle (deg)
216
camera_feedback.pitch_sensor*1e-2f, // pitch angle (deg)
217
camera_feedback.yaw_sensor*1e-2f, // yaw angle (deg)
218
0.0f, // focal length
219
CAMERA_FEEDBACK_PHOTO, // flags
220
camera_feedback.feedback_trigger_logged_count); // completed image captures
221
}
222
223
// send camera information message to GCS
224
void AP_Camera_Backend::send_camera_information(mavlink_channel_t chan) const
225
{
226
mavlink_camera_information_t camera_info;
227
#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
228
229
camera_info = _camera_info;
230
231
#else
232
233
memset(&camera_info, 0, sizeof(camera_info));
234
235
camera_info.focal_length = NaNf;
236
camera_info.sensor_size_h = NaNf;
237
camera_info.sensor_size_v = NaNf;
238
239
camera_info.flags = CAMERA_CAP_FLAGS_CAPTURE_IMAGE;
240
241
#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
242
243
// Set fixed fields
244
// lens_id is populated with the instance number, to disambiguate multiple cameras
245
camera_info.lens_id = _instance;
246
camera_info.gimbal_device_id = get_gimbal_device_id();
247
camera_info.time_boot_ms = AP_HAL::millis();
248
249
// Send CAMERA_INFORMATION message
250
mavlink_msg_camera_information_send_struct(chan, &camera_info);
251
}
252
253
#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
254
void AP_Camera_Backend::set_camera_information(mavlink_camera_information_t camera_info)
255
{
256
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Camera %u CAMERA_INFORMATION (%s %s) set from script", _instance, camera_info.vendor_name, camera_info.model_name);
257
_camera_info = camera_info;
258
};
259
#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
260
261
#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
262
// send video stream information message to GCS
263
void AP_Camera_Backend::send_video_stream_information(mavlink_channel_t chan) const
264
{
265
#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
266
267
// Send VIDEO_STREAM_INFORMATION message
268
mavlink_msg_video_stream_information_send_struct(chan, &_stream_info);
269
270
#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
271
}
272
#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
273
274
#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
275
void AP_Camera_Backend::set_stream_information(mavlink_video_stream_information_t stream_info)
276
{
277
_stream_info = stream_info;
278
};
279
#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
280
281
// send camera settings message to GCS
282
void AP_Camera_Backend::send_camera_settings(mavlink_channel_t chan) const
283
{
284
// send CAMERA_SETTINGS message
285
mavlink_msg_camera_settings_send(
286
chan,
287
AP_HAL::millis(), // time_boot_ms
288
CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey)
289
NaNf, // zoomLevel float, percentage from 0 to 100, NaN if unknown
290
NaNf); // focusLevel float, percentage from 0 to 100, NaN if unknown
291
}
292
293
#if AP_CAMERA_SEND_FOV_STATUS_ENABLED
294
// send camera field of view status
295
void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const
296
{
297
// getting corresponding mount instance for camera
298
AP_Mount* mount = AP::mount();
299
if (mount == nullptr) {
300
return;
301
}
302
303
// get latest POI from mount
304
Quaternion quat;
305
Location camera_loc;
306
Location poi_loc;
307
const bool have_poi_loc = mount->get_poi(get_mount_instance(), quat, camera_loc, poi_loc);
308
309
// if failed to get POI, get camera location directly from AHRS
310
// and attitude directly from mount
311
bool have_camera_loc = have_poi_loc;
312
if (!have_camera_loc) {
313
have_camera_loc = AP::ahrs().get_location(camera_loc);
314
mount->get_attitude_quaternion(get_mount_instance(), quat);
315
}
316
317
// calculate attitude quaternion in earth frame using AHRS yaw
318
Quaternion quat_ef;
319
quat_ef.from_euler(0, 0, AP::ahrs().get_yaw());
320
quat_ef *= quat;
321
322
// send camera fov status message only if the last calculated values aren't stale
323
const float quat_array[4] = {
324
quat_ef.q1,
325
quat_ef.q2,
326
quat_ef.q3,
327
quat_ef.q4
328
};
329
mavlink_msg_camera_fov_status_send(
330
chan,
331
AP_HAL::millis(),
332
have_camera_loc ? camera_loc.lat : INT32_MAX,
333
have_camera_loc ? camera_loc.lng : INT32_MAX,
334
have_camera_loc ? camera_loc.alt * 10 : INT32_MAX,
335
have_poi_loc ? poi_loc.lat : INT32_MAX,
336
have_poi_loc ? poi_loc.lng : INT32_MAX,
337
have_poi_loc ? poi_loc.alt * 10 : INT32_MAX,
338
quat_array,
339
horizontal_fov() > 0 ? horizontal_fov() : NaNf,
340
vertical_fov() > 0 ? vertical_fov() : NaNf
341
);
342
}
343
#endif
344
345
// send camera capture status message to GCS
346
void AP_Camera_Backend::send_camera_capture_status(mavlink_channel_t chan) const
347
{
348
// Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)
349
const uint8_t image_status = (time_interval_settings.num_remaining > 0) ? 2 : 0;
350
351
// send CAMERA_CAPTURE_STATUS message
352
mavlink_msg_camera_capture_status_send(
353
chan,
354
AP_HAL::millis(),
355
image_status,
356
0, // current status of video capturing (0: idle, 1: capture in progress)
357
static_cast<float>(time_interval_settings.time_interval_ms) / 1000.0, // image capture interval (s)
358
0, // elapsed time since recording started (ms)
359
NaNf, // available storage capacity (ms)
360
image_index); // total number of images captured
361
}
362
363
// setup a callback for a feedback pin. When on PX4 with the right FMU
364
// mode we can use the microsecond timer.
365
void AP_Camera_Backend::setup_feedback_callback()
366
{
367
if (_params.feedback_pin <= 0 || timer_installed || isr_installed) {
368
// invalid or already installed
369
return;
370
}
371
372
// ensure we are in input mode
373
hal.gpio->pinMode(_params.feedback_pin, HAL_GPIO_INPUT);
374
375
// enable pullup/pulldown
376
uint8_t trigger_polarity = _params.feedback_polarity == 0 ? 0 : 1;
377
hal.gpio->write(_params.feedback_pin, !trigger_polarity);
378
379
if (hal.gpio->attach_interrupt(_params.feedback_pin, FUNCTOR_BIND_MEMBER(&AP_Camera_Backend::feedback_pin_isr, void, uint8_t, bool, uint32_t),
380
trigger_polarity?AP_HAL::GPIO::INTERRUPT_RISING:AP_HAL::GPIO::INTERRUPT_FALLING)) {
381
isr_installed = true;
382
} else {
383
// install a 1kHz timer to check feedback pin
384
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Camera_Backend::feedback_pin_timer, void));
385
386
timer_installed = true;
387
}
388
}
389
390
// interrupt handler for interrupt based feedback trigger
391
void AP_Camera_Backend::feedback_pin_isr(uint8_t pin, bool high, uint32_t timestamp_us)
392
{
393
feedback_trigger_timestamp_us = timestamp_us;
394
feedback_trigger_count++;
395
}
396
397
// check if feedback pin is high for timer based feedback trigger, when
398
// attach_interrupt fails
399
void AP_Camera_Backend::feedback_pin_timer()
400
{
401
uint8_t pin_state = hal.gpio->read(_params.feedback_pin);
402
uint8_t trigger_polarity = _params.feedback_polarity == 0 ? 0 : 1;
403
if (pin_state == trigger_polarity &&
404
last_pin_state != trigger_polarity) {
405
feedback_trigger_timestamp_us = AP_HAL::micros();
406
feedback_trigger_count++;
407
}
408
last_pin_state = pin_state;
409
}
410
411
// check for feedback pin update and log if necessary
412
void AP_Camera_Backend::check_feedback()
413
{
414
if (feedback_trigger_logged_count != feedback_trigger_count) {
415
#if HAL_LOGGING_ENABLED
416
const uint32_t timestamp32 = feedback_trigger_timestamp_us;
417
#endif
418
feedback_trigger_logged_count = feedback_trigger_count;
419
420
// we should consider doing this inside the ISR and pin_timer
421
prep_mavlink_msg_camera_feedback(feedback_trigger_timestamp_us);
422
423
#if HAL_LOGGING_ENABLED
424
// log camera message
425
uint32_t tdiff = AP_HAL::micros() - timestamp32;
426
uint64_t timestamp = AP_HAL::micros64();
427
Write_Camera(timestamp - tdiff);
428
#endif
429
}
430
}
431
432
void AP_Camera_Backend::prep_mavlink_msg_camera_feedback(uint64_t timestamp_us)
433
{
434
const AP_AHRS &ahrs = AP::ahrs();
435
if (!ahrs.get_location(camera_feedback.location)) {
436
// completely ignore this failure! AHRS will provide its best guess.
437
}
438
camera_feedback.timestamp_us = timestamp_us;
439
camera_feedback.roll_sensor = ahrs.roll_sensor;
440
camera_feedback.pitch_sensor = ahrs.pitch_sensor;
441
camera_feedback.yaw_sensor = ahrs.yaw_sensor;
442
camera_feedback.feedback_trigger_logged_count = feedback_trigger_logged_count;
443
444
GCS_SEND_MESSAGE(MSG_CAMERA_FEEDBACK);
445
}
446
447
#if HAL_LOGGING_ENABLED
448
// log picture
449
void AP_Camera_Backend::log_picture()
450
{
451
const bool using_feedback_pin = _params.feedback_pin > 0;
452
453
if (!using_feedback_pin) {
454
// if we're using a feedback pin then when the event occurs we
455
// stash the feedback data. Since we're not using a feedback
456
// pin, we just use "now".
457
prep_mavlink_msg_camera_feedback(AP::gps().time_epoch_usec());
458
}
459
460
if (!using_feedback_pin) {
461
Write_Camera();
462
} else {
463
Write_Trigger();
464
}
465
}
466
#endif
467
468
#endif // AP_CAMERA_ENABLED
469
470