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.cpp
Views: 1798
1
#include "AP_Camera.h"
2
3
#if AP_CAMERA_ENABLED
4
5
#include <GCS_MAVLink/GCS.h>
6
#include <AP_Math/AP_Math.h>
7
#include <AP_HAL/AP_HAL.h>
8
#include <SRV_Channel/SRV_Channel.h>
9
#include <AP_Vehicle/AP_Vehicle.h>
10
#include "AP_Camera_Backend.h"
11
#include "AP_Camera_Servo.h"
12
#include "AP_Camera_Relay.h"
13
#include "AP_Camera_SoloGimbal.h"
14
#include "AP_Camera_Mount.h"
15
#include "AP_Camera_MAVLink.h"
16
#include "AP_Camera_MAVLinkCamV2.h"
17
#include "AP_Camera_Scripting.h"
18
#include "AP_RunCam.h"
19
20
const AP_Param::GroupInfo AP_Camera::var_info[] = {
21
22
// @Param: _MAX_ROLL
23
// @DisplayName: Maximum photo roll angle.
24
// @Description: Postpone shooting if roll is greater than limit. (0=Disable, will shoot regardless of roll).
25
// @User: Standard
26
// @Units: deg
27
// @Range: 0 180
28
AP_GROUPINFO("_MAX_ROLL", 7, AP_Camera, _max_roll, 0),
29
30
// @Param: _AUTO_ONLY
31
// @DisplayName: Distance-trigging in AUTO mode only
32
// @Description: When enabled, trigging by distance is done in AUTO mode only.
33
// @Values: 0:Always,1:Only when in AUTO
34
// @User: Standard
35
AP_GROUPINFO("_AUTO_ONLY", 10, AP_Camera, _auto_mode_only, 0),
36
37
// @Group: 1
38
// @Path: AP_Camera_Params.cpp
39
AP_SUBGROUPINFO(_params[0], "1", 12, AP_Camera, AP_Camera_Params),
40
41
#if AP_CAMERA_MAX_INSTANCES > 1
42
// @Group: 2
43
// @Path: AP_Camera_Params.cpp
44
AP_SUBGROUPINFO(_params[1], "2", 13, AP_Camera, AP_Camera_Params),
45
#endif
46
#if AP_CAMERA_RUNCAM_ENABLED
47
// @Group: 1_RC_
48
// @Path: AP_RunCam.cpp
49
AP_SUBGROUPVARPTR(_backends[0], "1_RC_", 14, AP_Camera, _backend_var_info[0]),
50
51
#if AP_CAMERA_MAX_INSTANCES > 1
52
// @Group: 2_RC_
53
// @Path: AP_RunCam.cpp
54
AP_SUBGROUPVARPTR(_backends[1], "2_RC_", 15, AP_Camera, _backend_var_info[1]),
55
#endif
56
#endif
57
AP_GROUPEND
58
};
59
60
#if AP_CAMERA_RUNCAM_ENABLED
61
const AP_Param::GroupInfo *AP_Camera::_backend_var_info[AP_CAMERA_MAX_INSTANCES];
62
#endif
63
64
extern const AP_HAL::HAL& hal;
65
66
AP_Camera::AP_Camera(uint32_t _log_camera_bit) :
67
log_camera_bit(_log_camera_bit)
68
{
69
AP_Param::setup_object_defaults(this, var_info);
70
_singleton = this;
71
}
72
73
// set camera trigger distance in a mission
74
void AP_Camera::set_trigger_distance(float distance_m)
75
{
76
WITH_SEMAPHORE(_rsem);
77
78
if (primary == nullptr) {
79
return;
80
}
81
primary->set_trigger_distance(distance_m);
82
}
83
84
// momentary switch to change camera between picture and video modes
85
void AP_Camera::cam_mode_toggle()
86
{
87
WITH_SEMAPHORE(_rsem);
88
89
if (primary == nullptr) {
90
return;
91
}
92
primary->cam_mode_toggle();
93
}
94
95
// take a picture
96
bool AP_Camera::take_picture()
97
{
98
WITH_SEMAPHORE(_rsem);
99
100
// call for each instance
101
bool success = false;
102
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
103
if (_backends[i] != nullptr) {
104
success |= _backends[i]->take_picture();
105
}
106
}
107
108
// return true if at least once pic taken
109
return success;
110
}
111
112
bool AP_Camera::take_picture(uint8_t instance)
113
{
114
WITH_SEMAPHORE(_rsem);
115
116
auto *backend = get_instance(instance);
117
if (backend == nullptr) {
118
return false;
119
}
120
return backend->take_picture();
121
}
122
123
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
124
// if instance is not provided, all available cameras affected
125
// time_interval_ms must be positive
126
// total_num is number of pictures to be taken, -1 means capture forever
127
// returns true if at least one camera is successful
128
bool AP_Camera::take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num)
129
{
130
WITH_SEMAPHORE(_rsem);
131
132
// sanity check time interval
133
if (time_interval_ms == 0) {
134
return false;
135
}
136
137
// call for all instances
138
bool success = false;
139
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
140
if (_backends[i] != nullptr) {
141
_backends[i]->take_multiple_pictures(time_interval_ms, total_num);
142
success = true;
143
}
144
}
145
146
// return true if at least once backend was successful
147
return success;
148
}
149
150
bool AP_Camera::take_multiple_pictures(uint8_t instance, uint32_t time_interval_ms, int16_t total_num)
151
{
152
WITH_SEMAPHORE(_rsem);
153
154
// sanity check time interval
155
if (time_interval_ms == 0) {
156
return false;
157
}
158
159
auto *backend = get_instance(instance);
160
if (backend == nullptr) {
161
return false;
162
}
163
backend->take_multiple_pictures(time_interval_ms, total_num);
164
return true;
165
}
166
167
// stop capturing multiple image sequence
168
void AP_Camera::stop_capture()
169
{
170
WITH_SEMAPHORE(_rsem);
171
172
// call for each instance
173
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
174
if (_backends[i] != nullptr) {
175
_backends[i]->stop_capture();
176
}
177
}
178
}
179
180
bool AP_Camera::stop_capture(uint8_t instance)
181
{
182
WITH_SEMAPHORE(_rsem);
183
184
auto *backend = get_instance(instance);
185
if (backend == nullptr) {
186
return false;
187
}
188
backend->stop_capture();
189
return true;
190
}
191
192
// start/stop recording video
193
// start_recording should be true to start recording, false to stop recording
194
bool AP_Camera::record_video(bool start_recording)
195
{
196
WITH_SEMAPHORE(_rsem);
197
198
if (primary == nullptr) {
199
return false;
200
}
201
return primary->record_video(start_recording);
202
}
203
204
// detect and initialise backends
205
void AP_Camera::init()
206
{
207
// check init has not been called before
208
if (primary != nullptr) {
209
return;
210
}
211
212
// perform any required parameter conversion
213
convert_params();
214
215
// create each instance
216
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
217
switch ((CameraType)_params[instance].type.get()) {
218
#if AP_CAMERA_SERVO_ENABLED
219
case CameraType::SERVO:
220
_backends[instance] = NEW_NOTHROW AP_Camera_Servo(*this, _params[instance], instance);
221
break;
222
#endif
223
#if AP_CAMERA_RELAY_ENABLED
224
case CameraType::RELAY:
225
_backends[instance] = NEW_NOTHROW AP_Camera_Relay(*this, _params[instance], instance);
226
break;
227
#endif
228
#if AP_CAMERA_SOLOGIMBAL_ENABLED
229
// check for GoPro in Solo camera
230
case CameraType::SOLOGIMBAL:
231
_backends[instance] = NEW_NOTHROW AP_Camera_SoloGimbal(*this, _params[instance], instance);
232
break;
233
#endif
234
#if AP_CAMERA_MOUNT_ENABLED
235
// check for Mount camera
236
case CameraType::MOUNT:
237
_backends[instance] = NEW_NOTHROW AP_Camera_Mount(*this, _params[instance], instance);
238
break;
239
#endif
240
#if AP_CAMERA_MAVLINK_ENABLED
241
// check for MAVLink enabled camera driver
242
case CameraType::MAVLINK:
243
_backends[instance] = NEW_NOTHROW AP_Camera_MAVLink(*this, _params[instance], instance);
244
break;
245
#endif
246
#if AP_CAMERA_MAVLINKCAMV2_ENABLED
247
// check for MAVLink Camv2 driver
248
case CameraType::MAVLINK_CAMV2:
249
_backends[instance] = NEW_NOTHROW AP_Camera_MAVLinkCamV2(*this, _params[instance], instance);
250
break;
251
#endif
252
#if AP_CAMERA_SCRIPTING_ENABLED
253
// check for Scripting driver
254
case CameraType::SCRIPTING:
255
_backends[instance] = NEW_NOTHROW AP_Camera_Scripting(*this, _params[instance], instance);
256
break;
257
#endif
258
#if AP_CAMERA_RUNCAM_ENABLED
259
// check for RunCam driver
260
case CameraType::RUNCAM:
261
if (_backends[instance] == nullptr) { // may have already been created by the conversion code
262
_backends[instance] = NEW_NOTHROW AP_RunCam(*this, _params[instance], instance, _runcam_instances);
263
_backend_var_info[instance] = AP_RunCam::var_info;
264
AP_Param::load_object_from_eeprom(_backends[instance], _backend_var_info[instance]);
265
_runcam_instances++;
266
}
267
break;
268
#endif
269
case CameraType::NONE:
270
break;
271
}
272
273
// set primary to first non-null instance
274
if (primary == nullptr) {
275
primary = _backends[instance];
276
}
277
}
278
279
// init each instance, do it after all instances were created, so that they all know things
280
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
281
if (_backends[instance] != nullptr) {
282
_backends[instance]->init();
283
}
284
}
285
}
286
287
// handle incoming mavlink messages
288
void AP_Camera::handle_message(mavlink_channel_t chan, const mavlink_message_t &msg)
289
{
290
WITH_SEMAPHORE(_rsem);
291
292
if (msg.msgid == MAVLINK_MSG_ID_DIGICAM_CONTROL) {
293
// decode deprecated MavLink message that controls camera.
294
__mavlink_digicam_control_t packet;
295
mavlink_msg_digicam_control_decode(&msg, &packet);
296
control(packet.session, packet.zoom_pos, packet.zoom_step, packet.focus_lock, packet.shot, packet.command_id);
297
return;
298
}
299
300
// call each instance
301
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
302
if (_backends[instance] != nullptr) {
303
_backends[instance]->handle_message(chan, msg);
304
}
305
}
306
}
307
308
// handle command_long mavlink messages
309
MAV_RESULT AP_Camera::handle_command(const mavlink_command_int_t &packet)
310
{
311
switch (packet.command) {
312
case MAV_CMD_DO_DIGICAM_CONFIGURE:
313
configure(packet.param1, packet.param2, packet.param3, packet.param4, packet.x, packet.y, packet.z);
314
return MAV_RESULT_ACCEPTED;
315
case MAV_CMD_DO_DIGICAM_CONTROL:
316
control(packet.param1, packet.param2, packet.param3, packet.param4, packet.x, packet.y);
317
return MAV_RESULT_ACCEPTED;
318
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
319
set_trigger_distance(packet.param1);
320
if (is_equal(packet.param3, 1.0f)) {
321
take_picture();
322
}
323
return MAV_RESULT_ACCEPTED;
324
case MAV_CMD_SET_CAMERA_ZOOM:
325
if (is_equal(packet.param1, (float)ZOOM_TYPE_CONTINUOUS) &&
326
set_zoom(ZoomType::RATE, packet.param2)) {
327
return MAV_RESULT_ACCEPTED;
328
}
329
if (is_equal(packet.param1, (float)ZOOM_TYPE_RANGE) &&
330
set_zoom(ZoomType::PCT, packet.param2)) {
331
return MAV_RESULT_ACCEPTED;
332
}
333
return MAV_RESULT_UNSUPPORTED;
334
case MAV_CMD_SET_CAMERA_FOCUS:
335
// accept any of the auto focus types
336
switch ((SET_FOCUS_TYPE)packet.param1) {
337
case FOCUS_TYPE_AUTO:
338
case FOCUS_TYPE_AUTO_SINGLE:
339
case FOCUS_TYPE_AUTO_CONTINUOUS:
340
return (MAV_RESULT)set_focus(FocusType::AUTO, 0);
341
case FOCUS_TYPE_CONTINUOUS:
342
// accept continuous manual focus
343
return (MAV_RESULT)set_focus(FocusType::RATE, packet.param2);
344
// accept focus as percentage
345
case FOCUS_TYPE_RANGE:
346
return (MAV_RESULT)set_focus(FocusType::PCT, packet.param2);
347
case SET_FOCUS_TYPE_ENUM_END:
348
case FOCUS_TYPE_STEP:
349
case FOCUS_TYPE_METERS:
350
// unsupported focus (bad parameter)
351
break;
352
}
353
return MAV_RESULT_DENIED;
354
355
#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
356
case MAV_CMD_SET_CAMERA_SOURCE:
357
// sanity check instance
358
if (is_negative(packet.param1) || packet.param1 > AP_CAMERA_MAX_INSTANCES) {
359
return MAV_RESULT_DENIED;
360
}
361
if (is_zero(packet.param1)) {
362
// set camera source for all backends
363
bool accepted = false;
364
for (uint8_t i = 0; i < ARRAY_SIZE(_backends); i++) {
365
if (_backends[i] != nullptr) {
366
accepted |= set_camera_source(i, (AP_Camera::CameraSource)packet.param2, (AP_Camera::CameraSource)packet.param3);
367
}
368
}
369
return accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED;
370
}
371
if (set_camera_source(packet.param1-1, (AP_Camera::CameraSource)packet.param2, (AP_Camera::CameraSource)packet.param3)) {
372
return MAV_RESULT_ACCEPTED;
373
}
374
return MAV_RESULT_DENIED;
375
#endif
376
377
case MAV_CMD_IMAGE_START_CAPTURE:
378
// param1 : camera id
379
// param2 : interval (in seconds)
380
// param3 : total num images
381
// sanity check instance
382
if (is_negative(packet.param1)) {
383
return MAV_RESULT_UNSUPPORTED;
384
}
385
// check if this is a single picture request (e.g. total images is 1 or interval and total images are zero)
386
if (is_equal(packet.param3, 1.0f) ||
387
(is_zero(packet.param2) && is_zero(packet.param3))) {
388
if (is_zero(packet.param1)) {
389
// take pictures for every backend
390
return take_picture() ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
391
}
392
// take picture for specified instance
393
return take_picture(packet.param1-1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
394
} else if (is_zero(packet.param3)) {
395
// multiple picture request, take pictures forever
396
if (is_zero(packet.param1)) {
397
// take pictures for every backend
398
return take_multiple_pictures(packet.param2*1000, -1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
399
}
400
return take_multiple_pictures(packet.param1-1, packet.param2*1000, -1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
401
} else {
402
// take multiple pictures equal to the number specified in param3
403
if (is_zero(packet.param1)) {
404
// take pictures for every backend
405
return take_multiple_pictures(packet.param2*1000, packet.param3) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
406
}
407
return take_multiple_pictures(packet.param1-1, packet.param2*1000, packet.param3) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
408
}
409
case MAV_CMD_IMAGE_STOP_CAPTURE:
410
// param1 : camera id
411
if (is_negative(packet.param1)) {
412
return MAV_RESULT_UNSUPPORTED;
413
}
414
if (is_zero(packet.param1)) {
415
// stop capture for every backend
416
stop_capture();
417
return MAV_RESULT_ACCEPTED;
418
}
419
if (stop_capture(packet.param1-1)) {
420
return MAV_RESULT_ACCEPTED;
421
}
422
return MAV_RESULT_UNSUPPORTED;
423
case MAV_CMD_CAMERA_TRACK_POINT:
424
if (set_tracking(TrackingType::TRK_POINT, Vector2f{packet.param1, packet.param2}, Vector2f{})) {
425
return MAV_RESULT_ACCEPTED;
426
}
427
return MAV_RESULT_UNSUPPORTED;
428
case MAV_CMD_CAMERA_TRACK_RECTANGLE:
429
if (set_tracking(TrackingType::TRK_RECTANGLE, Vector2f{packet.param1, packet.param2}, Vector2f{packet.param3, packet.param4})) {
430
return MAV_RESULT_ACCEPTED;
431
}
432
return MAV_RESULT_UNSUPPORTED;
433
case MAV_CMD_CAMERA_STOP_TRACKING:
434
if (set_tracking(TrackingType::TRK_NONE, Vector2f{}, Vector2f{})) {
435
return MAV_RESULT_ACCEPTED;
436
}
437
return MAV_RESULT_UNSUPPORTED;
438
case MAV_CMD_VIDEO_START_CAPTURE:
439
case MAV_CMD_VIDEO_STOP_CAPTURE:
440
{
441
bool success = false;
442
const bool start_recording = (packet.command == MAV_CMD_VIDEO_START_CAPTURE);
443
const uint8_t stream_id = packet.param1; // Stream ID
444
if (stream_id == 0) {
445
// stream id of 0 interpreted as primary camera
446
success = record_video(start_recording);
447
} else {
448
// convert stream id to instance id
449
success = record_video(stream_id - 1, start_recording);
450
}
451
if (success) {
452
return MAV_RESULT_ACCEPTED;
453
} else {
454
return MAV_RESULT_FAILED;
455
}
456
}
457
default:
458
return MAV_RESULT_UNSUPPORTED;
459
}
460
}
461
462
// send a mavlink message; returns false if there was not space to
463
// send the message, true otherwise
464
bool AP_Camera::send_mavlink_message(GCS_MAVLINK &link, const enum ap_message msg_id)
465
{
466
const auto chan = link.get_chan();
467
468
switch (msg_id) {
469
case MSG_CAMERA_FEEDBACK:
470
CHECK_PAYLOAD_SIZE2(CAMERA_FEEDBACK);
471
send_feedback(chan);
472
break;
473
case MSG_CAMERA_INFORMATION:
474
CHECK_PAYLOAD_SIZE2(CAMERA_INFORMATION);
475
send_camera_information(chan);
476
break;
477
case MSG_CAMERA_SETTINGS:
478
CHECK_PAYLOAD_SIZE2(CAMERA_SETTINGS);
479
send_camera_settings(chan);
480
break;
481
#if AP_CAMERA_SEND_FOV_STATUS_ENABLED
482
case MSG_CAMERA_FOV_STATUS:
483
CHECK_PAYLOAD_SIZE2(CAMERA_FOV_STATUS);
484
send_camera_fov_status(chan);
485
break;
486
#endif
487
case MSG_CAMERA_CAPTURE_STATUS:
488
CHECK_PAYLOAD_SIZE2(CAMERA_CAPTURE_STATUS);
489
send_camera_capture_status(chan);
490
break;
491
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
492
case MSG_CAMERA_THERMAL_RANGE:
493
CHECK_PAYLOAD_SIZE2(CAMERA_THERMAL_RANGE);
494
send_camera_thermal_range(chan);
495
break;
496
#endif
497
#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
498
case MSG_VIDEO_STREAM_INFORMATION:
499
CHECK_PAYLOAD_SIZE2(VIDEO_STREAM_INFORMATION);
500
send_video_stream_information(chan);
501
break;
502
#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
503
504
default:
505
// should not reach this; should only be called for specific IDs
506
break;
507
}
508
509
return true;
510
}
511
512
// set camera trigger distance in a mission
513
void AP_Camera::set_trigger_distance(uint8_t instance, float distance_m)
514
{
515
WITH_SEMAPHORE(_rsem);
516
517
auto *backend = get_instance(instance);
518
if (backend == nullptr) {
519
return;
520
}
521
522
// call backend
523
backend->set_trigger_distance(distance_m);
524
}
525
526
// momentary switch to change camera between picture and video modes
527
void AP_Camera::cam_mode_toggle(uint8_t instance)
528
{
529
WITH_SEMAPHORE(_rsem);
530
531
auto *backend = get_instance(instance);
532
if (backend == nullptr) {
533
return;
534
}
535
536
// call backend
537
backend->cam_mode_toggle();
538
}
539
540
// configure camera
541
void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time)
542
{
543
WITH_SEMAPHORE(_rsem);
544
545
if (primary == nullptr) {
546
return;
547
}
548
primary->configure(shooting_mode, shutter_speed, aperture, ISO, exposure_type, cmd_id, engine_cutoff_time);
549
}
550
551
void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time)
552
{
553
WITH_SEMAPHORE(_rsem);
554
555
auto *backend = get_instance(instance);
556
if (backend == nullptr) {
557
return;
558
}
559
560
// call backend
561
backend->configure(shooting_mode, shutter_speed, aperture, ISO, exposure_type, cmd_id, engine_cutoff_time);
562
}
563
564
// handle camera control
565
void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)
566
{
567
WITH_SEMAPHORE(_rsem);
568
569
if (primary == nullptr) {
570
return;
571
}
572
primary->control(session, zoom_pos, zoom_step, focus_lock, shooting_cmd, cmd_id);
573
}
574
575
void AP_Camera::control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)
576
{
577
WITH_SEMAPHORE(_rsem);
578
579
auto *backend = get_instance(instance);
580
if (backend == nullptr) {
581
return;
582
}
583
584
// call backend
585
backend->control(session, zoom_pos, zoom_step, focus_lock, shooting_cmd, cmd_id);
586
}
587
588
/*
589
Send camera feedback to the GCS
590
*/
591
void AP_Camera::send_feedback(mavlink_channel_t chan)
592
{
593
WITH_SEMAPHORE(_rsem);
594
595
// call each instance
596
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
597
if (_backends[instance] != nullptr) {
598
_backends[instance]->send_camera_feedback(chan);
599
}
600
}
601
}
602
603
// send camera information message to GCS
604
void AP_Camera::send_camera_information(mavlink_channel_t chan)
605
{
606
WITH_SEMAPHORE(_rsem);
607
608
// call each instance
609
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
610
if (_backends[instance] != nullptr) {
611
_backends[instance]->send_camera_information(chan);
612
}
613
}
614
}
615
616
#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
617
// send video stream information message to GCS
618
void AP_Camera::send_video_stream_information(mavlink_channel_t chan)
619
{
620
WITH_SEMAPHORE(_rsem);
621
622
// call each instance
623
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
624
if (_backends[instance] != nullptr) {
625
_backends[instance]->send_video_stream_information(chan);
626
}
627
}
628
}
629
#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED
630
631
// send camera settings message to GCS
632
void AP_Camera::send_camera_settings(mavlink_channel_t chan)
633
{
634
WITH_SEMAPHORE(_rsem);
635
636
// call each instance
637
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
638
if (_backends[instance] != nullptr) {
639
_backends[instance]->send_camera_settings(chan);
640
}
641
}
642
}
643
644
#if AP_CAMERA_SEND_FOV_STATUS_ENABLED
645
// send camera field of view status
646
void AP_Camera::send_camera_fov_status(mavlink_channel_t chan)
647
{
648
WITH_SEMAPHORE(_rsem);
649
650
// call each instance
651
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
652
if (_backends[instance] != nullptr) {
653
_backends[instance]->send_camera_fov_status(chan);
654
}
655
}
656
}
657
#endif
658
659
// send camera capture status message to GCS
660
void AP_Camera::send_camera_capture_status(mavlink_channel_t chan)
661
{
662
WITH_SEMAPHORE(_rsem);
663
664
// call each instance
665
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
666
if (_backends[instance] != nullptr) {
667
_backends[instance]->send_camera_capture_status(chan);
668
}
669
}
670
}
671
672
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
673
// send camera thermal range message to GCS
674
void AP_Camera::send_camera_thermal_range(mavlink_channel_t chan)
675
{
676
WITH_SEMAPHORE(_rsem);
677
678
// call each instance
679
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
680
if (_backends[instance] != nullptr) {
681
_backends[instance]->send_camera_thermal_range(chan);
682
}
683
}
684
}
685
#endif
686
687
/*
688
update; triggers by distance moved and camera trigger
689
*/
690
void AP_Camera::update()
691
{
692
WITH_SEMAPHORE(_rsem);
693
694
// call each instance
695
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
696
if (_backends[instance] != nullptr) {
697
_backends[instance]->update();
698
}
699
}
700
}
701
702
// start/stop recording video. returns true on success
703
// start_recording should be true to start recording, false to stop recording
704
bool AP_Camera::record_video(uint8_t instance, bool start_recording)
705
{
706
WITH_SEMAPHORE(_rsem);
707
708
auto *backend = get_instance(instance);
709
if (backend == nullptr) {
710
return false;
711
}
712
713
// call backend
714
return backend->record_video(start_recording);
715
}
716
717
// zoom specified as a rate or percentage
718
bool AP_Camera::set_zoom(ZoomType zoom_type, float zoom_value)
719
{
720
WITH_SEMAPHORE(_rsem);
721
722
if (primary == nullptr) {
723
return false;
724
}
725
return primary->set_zoom(zoom_type, zoom_value);
726
}
727
728
// zoom specified as a rate or percentage
729
bool AP_Camera::set_zoom(uint8_t instance, ZoomType zoom_type, float zoom_value)
730
{
731
WITH_SEMAPHORE(_rsem);
732
733
auto *backend = get_instance(instance);
734
if (backend == nullptr) {
735
return false;
736
}
737
738
// call each instance
739
return backend->set_zoom(zoom_type, zoom_value);
740
}
741
742
743
// set focus specified as rate, percentage or auto
744
// focus in = -1, focus hold = 0, focus out = 1
745
SetFocusResult AP_Camera::set_focus(FocusType focus_type, float focus_value)
746
{
747
WITH_SEMAPHORE(_rsem);
748
749
if (primary == nullptr) {
750
return SetFocusResult::FAILED;
751
}
752
return primary->set_focus(focus_type, focus_value);
753
}
754
755
// set focus specified as rate, percentage or auto
756
// focus in = -1, focus hold = 0, focus out = 1
757
SetFocusResult AP_Camera::set_focus(uint8_t instance, FocusType focus_type, float focus_value)
758
{
759
WITH_SEMAPHORE(_rsem);
760
761
auto *backend = get_instance(instance);
762
if (backend == nullptr) {
763
return SetFocusResult::FAILED;
764
}
765
766
// call each instance
767
return backend->set_focus(focus_type, focus_value);
768
}
769
770
// set tracking to none, point or rectangle (see TrackingType enum)
771
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
772
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
773
bool AP_Camera::set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2)
774
{
775
WITH_SEMAPHORE(_rsem);
776
777
if (primary == nullptr) {
778
return false;
779
}
780
return primary->set_tracking(tracking_type, p1, p2);
781
}
782
783
// set tracking to none, point or rectangle (see TrackingType enum)
784
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
785
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
786
bool AP_Camera::set_tracking(uint8_t instance, TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2)
787
{
788
WITH_SEMAPHORE(_rsem);
789
790
auto *backend = get_instance(instance);
791
if (backend == nullptr) {
792
return false;
793
}
794
795
// call each instance
796
return backend->set_tracking(tracking_type, p1, p2);
797
}
798
799
#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
800
// set camera lens as a value from 0 to 5
801
bool AP_Camera::set_lens(uint8_t lens)
802
{
803
WITH_SEMAPHORE(_rsem);
804
805
if (primary == nullptr) {
806
return false;
807
}
808
return primary->set_lens(lens);
809
}
810
811
bool AP_Camera::set_lens(uint8_t instance, uint8_t lens)
812
{
813
WITH_SEMAPHORE(_rsem);
814
815
auto *backend = get_instance(instance);
816
if (backend == nullptr) {
817
return false;
818
}
819
820
// call instance
821
return backend->set_lens(lens);
822
}
823
824
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
825
bool AP_Camera::set_camera_source(uint8_t instance, CameraSource primary_source, CameraSource secondary_source)
826
{
827
WITH_SEMAPHORE(_rsem);
828
829
auto *backend = get_instance(instance);
830
if (backend == nullptr) {
831
return false;
832
}
833
834
// call instance
835
return backend->set_camera_source(primary_source, secondary_source);
836
}
837
#endif // AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
838
839
#if AP_CAMERA_SCRIPTING_ENABLED
840
// accessor to allow scripting backend to retrieve state
841
// returns true on success and cam_state is filled in
842
bool AP_Camera::get_state(uint8_t instance, camera_state_t& cam_state)
843
{
844
WITH_SEMAPHORE(_rsem);
845
846
auto *backend = get_instance(instance);
847
if (backend == nullptr) {
848
return false;
849
}
850
return backend->get_state(cam_state);
851
}
852
853
// change camera settings not normally used by autopilot
854
bool AP_Camera::change_setting(uint8_t instance, CameraSetting setting, float value)
855
{
856
WITH_SEMAPHORE(_rsem);
857
858
auto *backend = get_instance(instance);
859
if (backend == nullptr) {
860
return false;
861
}
862
return backend->change_setting(setting, value);
863
}
864
865
#endif // #if AP_CAMERA_SCRIPTING_ENABLED
866
867
868
#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
869
void AP_Camera::set_camera_information(mavlink_camera_information_t camera_info)
870
{
871
WITH_SEMAPHORE(_rsem);
872
873
if (primary == nullptr) {
874
return;
875
}
876
return primary->set_camera_information(camera_info);
877
}
878
879
void AP_Camera::set_camera_information(uint8_t instance, mavlink_camera_information_t camera_info)
880
{
881
WITH_SEMAPHORE(_rsem);
882
883
auto *backend = get_instance(instance);
884
if (backend == nullptr) {
885
return;
886
}
887
888
// call instance
889
backend->set_camera_information(camera_info);
890
}
891
892
void AP_Camera::set_stream_information(mavlink_video_stream_information_t stream_info)
893
{
894
WITH_SEMAPHORE(_rsem);
895
896
if (primary == nullptr) {
897
return;
898
}
899
return primary->set_stream_information(stream_info);
900
}
901
902
void AP_Camera::set_stream_information(uint8_t instance, mavlink_video_stream_information_t stream_info)
903
{
904
WITH_SEMAPHORE(_rsem);
905
906
auto *backend = get_instance(instance);
907
if (backend == nullptr) {
908
return;
909
}
910
911
// call instance
912
backend->set_stream_information(stream_info);
913
}
914
#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
915
916
// return backend for instance number
917
AP_Camera_Backend *AP_Camera::get_instance(uint8_t instance) const
918
{
919
if (instance >= ARRAY_SIZE(_backends)) {
920
return nullptr;
921
}
922
return _backends[instance];
923
}
924
925
// perform any required parameter conversion
926
void AP_Camera::convert_params()
927
{
928
// exit immediately if CAM1_TYPE has already been configured
929
if (_params[0].type.configured()
930
#if AP_CAMERA_RUNCAM_ENABLED
931
&& _params[1].type.configured()
932
#endif
933
) {
934
return;
935
}
936
937
// PARAMETER_CONVERSION - Added: Feb-2023 ahead of 4.4 release
938
939
// convert CAM_TRIGG_TYPE to CAM1_TYPE
940
int8_t cam_trigg_type = 0;
941
int8_t cam1_type = 0;
942
IGNORE_RETURN(AP_Param::get_param_by_index(this, 0, AP_PARAM_INT8, &cam_trigg_type));
943
if ((cam_trigg_type == 0) && SRV_Channels::function_assigned(SRV_Channel::k_cam_trigger)) {
944
// CAM_TRIGG_TYPE was 0 (Servo) and camera trigger servo function was assigned so set CAM1_TYPE = 1 (Servo)
945
cam1_type = 1;
946
}
947
if ((cam_trigg_type >= 1) && (cam_trigg_type <= 3)) {
948
// CAM_TRIGG_TYPE was set to Relay, GoPro or Mount
949
cam1_type = cam_trigg_type + 1;
950
}
951
_params[0].type.set_and_save(cam1_type);
952
953
#if AP_CAMERA_RUNCAM_ENABLED
954
// RunCam PARAMETER_CONVERSION - Added: Nov-2024 ahead of 4.7 release
955
956
// Since slot 1 is essentially used by the trigger type, we will use slot 2 for runcam
957
int8_t rc_type = 0;
958
// find vehicle's top level key
959
uint16_t k_param_vehicle_key;
960
if (!AP_Param::find_top_level_key_by_pointer(AP::vehicle(), k_param_vehicle_key)) {
961
return;
962
}
963
964
// RunCam protocol configured so set cam type to RunCam
965
bool rc_protocol_configured = false;
966
AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();
967
if (serial_manager && serial_manager->find_serial(AP_SerialManager::SerialProtocol_RunCam, 0)) {
968
rc_protocol_configured = true;
969
}
970
971
const AP_Param::ConversionInfo rc_type_info = {
972
k_param_vehicle_key, AP_GROUP_ELEM_IDX(1, 1), AP_PARAM_INT8, "CAM_RC_TYPE"
973
};
974
AP_Int8 rc_type_old;
975
const bool found_rc_type = AP_Param::find_old_parameter(&rc_type_info, &rc_type_old);
976
977
if (rc_protocol_configured || (found_rc_type && rc_type_old.get() > 0)) {
978
rc_type = int8_t(CameraType::RUNCAM);
979
_backends[1] = NEW_NOTHROW AP_RunCam(*this, _params[1], 1, _runcam_instances);
980
_backend_var_info[1] = AP_RunCam::var_info;
981
AP_Param::convert_class(k_param_vehicle_key, &_backends[1], _backend_var_info[1], 1, false);
982
AP_Param::invalidate_count();
983
_runcam_instances++;
984
}
985
986
_params[1].type.set_and_save(rc_type);
987
#endif // AP_CAMERA_RUNCAM_ENABLED
988
989
// convert CAM_DURATION (in deci-seconds) to CAM1_DURATION (in seconds)
990
int8_t cam_duration = 0;
991
if (AP_Param::get_param_by_index(this, 1, AP_PARAM_INT8, &cam_duration) && (cam_duration > 0)) {
992
_params[0].trigger_duration.set_and_save(cam_duration * 0.1);
993
}
994
995
// convert CAM_MIN_INTERVAL (in milliseconds) to CAM1__INTRVAL_MIN (in seconds)
996
int16_t cam_min_interval = 0;
997
if (AP_Param::get_param_by_index(this, 6, AP_PARAM_INT16, &cam_min_interval) && (cam_min_interval > 0)) {
998
_params[0].interval_min.set_and_save(cam_min_interval * 0.001f);
999
}
1000
1001
// find Camera's top level key
1002
uint16_t k_param_camera_key;
1003
if (!AP_Param::find_top_level_key_by_pointer(this, k_param_camera_key)) {
1004
return;
1005
}
1006
1007
// table parameters to convert without scaling
1008
static const AP_Param::ConversionInfo camera_param_conversion_info[] {
1009
{ k_param_camera_key, 2, AP_PARAM_INT16, "CAM1_SERVO_ON" },
1010
{ k_param_camera_key, 3, AP_PARAM_INT16, "CAM1_SERVO_OFF" },
1011
{ k_param_camera_key, 4, AP_PARAM_FLOAT, "CAM1_TRIGG_DIST" },
1012
{ k_param_camera_key, 5, AP_PARAM_INT8, "CAM1_RELAY_ON" },
1013
{ k_param_camera_key, 8, AP_PARAM_INT8, "CAM1_FEEDBAK_PIN" },
1014
{ k_param_camera_key, 9, AP_PARAM_INT8, "CAM1_FEEDBAK_POL" },
1015
};
1016
uint8_t table_size = ARRAY_SIZE(camera_param_conversion_info);
1017
for (uint8_t i=0; i<table_size; i++) {
1018
AP_Param::convert_old_parameter(&camera_param_conversion_info[i], 1.0f);
1019
}
1020
}
1021
1022
#if AP_RELAY_ENABLED
1023
// Return true and the relay index if relay camera backend is selected, used for conversion to relay functions
1024
bool AP_Camera::get_legacy_relay_index(int8_t &index) const
1025
{
1026
// PARAMETER_CONVERSION - Added: Dec-2023
1027
1028
// Note that this assumes that the camera param conversion has already been done
1029
// Copter, Plane, Sub and Rover all have both relay and camera and all init relay first
1030
// This will only be a issue if the relay and camera conversion were done at once, if the user skipped 4.4
1031
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
1032
#if AP_CAMERA_RELAY_ENABLED
1033
if ((CameraType)_params[i].type.get() == CameraType::RELAY) {
1034
// Camera was hard coded to relay 0
1035
index = 0;
1036
return true;
1037
}
1038
#endif
1039
}
1040
return false;
1041
}
1042
#endif
1043
1044
// singleton instance
1045
AP_Camera *AP_Camera::_singleton;
1046
1047
namespace AP {
1048
1049
AP_Camera *camera()
1050
{
1051
return AP_Camera::get_singleton();
1052
}
1053
1054
}
1055
1056
#endif
1057
1058