• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

mavlink / MAVSDK / 18289533825

06 Oct 2025 05:42PM UTC coverage: 47.607% (+0.01%) from 47.597%
18289533825

push

github

web-flow
Merge pull request #2674 from mavlink/update-dependencies

Update openssl, boringssl and curl

17038 of 35789 relevant lines covered (47.61%)

453.52 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

55.46
/src/mavsdk/plugins/camera/camera_impl.cpp
1
#include "camera_impl.h"
2
#include "camera_definition.h"
3
#include "system.h"
4
#include "unused.h"
5
#include "callback_list.tpp"
6
#include "fs_utils.h"
7
#include "string_utils.h"
8
#include "math_utils.h"
9

10
#if BUILD_WITHOUT_CURL != 1
11
#include "http_loader.h"
12
#endif
13

14
#include <algorithm>
15
#include <cassert>
16
#include <cmath>
17
#include <chrono>
18
#include <iterator>
19
#include <filesystem>
20
#include <functional>
21
#include <string>
22
#include <thread>
23

24
namespace mavsdk {
25

26
template class CallbackList<Camera::Mode>;
27
template class CallbackList<std::vector<Camera::Setting>>;
28
template class CallbackList<std::vector<Camera::SettingOptions>>;
29
template class CallbackList<Camera::CaptureInfo>;
30
template class CallbackList<Camera::VideoStreamInfo>;
31
template class CallbackList<Camera::Storage>;
32

33
CameraImpl::CameraImpl(System& system) : PluginImplBase(system)
×
34
{
35
    _system_impl->register_plugin(this);
×
36
}
×
37

38
CameraImpl::CameraImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
9✔
39
{
40
    _system_impl->register_plugin(this);
9✔
41
}
9✔
42

43
CameraImpl::~CameraImpl()
18✔
44
{
45
    _system_impl->unregister_plugin(this);
9✔
46
}
18✔
47

48
void CameraImpl::init()
9✔
49
{
50
    if (const char* env_p = std::getenv("MAVSDK_CAMERA_DEBUGGING")) {
9✔
51
        if (std::string(env_p) == "1") {
×
52
            LogDebug() << "Camera debugging is on.";
×
53
            _debugging = true;
×
54
        }
55
    }
56

57
    const auto cache_dir_option = get_cache_directory();
9✔
58
    if (cache_dir_option) {
9✔
59
        _file_cache.emplace(cache_dir_option.value() / "camera", 50, true);
9✔
60
    } else {
61
        LogErr() << "Failed to get cache directory";
×
62
    }
63

64
    const auto tmp_option = create_tmp_directory("mavsdk-component-metadata");
18✔
65
    if (tmp_option) {
9✔
66
        _tmp_download_path = tmp_option.value();
9✔
67
    } else {
68
        _tmp_download_path = "./mavsdk-component-metadata";
×
69
        std::error_code err;
×
70
        std::filesystem::create_directory(_tmp_download_path, err);
×
71
    }
72

73
    _system_impl->register_mavlink_message_handler(
9✔
74
        MAVLINK_MSG_ID_HEARTBEAT,
75
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
22✔
76
        this);
77

78
    _system_impl->register_mavlink_message_handler(
9✔
79
        MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS,
80
        [this](const mavlink_message_t& message) { process_camera_capture_status(message); },
13✔
81
        this);
82

83
    _system_impl->register_mavlink_message_handler(
9✔
84
        MAVLINK_MSG_ID_STORAGE_INFORMATION,
85
        [this](const mavlink_message_t& message) { process_storage_information(message); },
2✔
86
        this);
87

88
    _system_impl->register_mavlink_message_handler(
9✔
89
        MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED,
90
        [this](const mavlink_message_t& message) { process_camera_image_captured(message); },
4✔
91
        this);
92

93
    _system_impl->register_mavlink_message_handler(
9✔
94
        MAVLINK_MSG_ID_CAMERA_SETTINGS,
95
        [this](const mavlink_message_t& message) { process_camera_settings(message); },
9✔
96
        this);
97

98
    _system_impl->register_mavlink_message_handler(
9✔
99
        MAVLINK_MSG_ID_CAMERA_INFORMATION,
100
        [this](const mavlink_message_t& message) { process_camera_information(message); },
9✔
101
        this);
102

103
    _system_impl->register_mavlink_message_handler(
9✔
104
        MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION,
105
        [this](const mavlink_message_t& message) { process_video_information(message); },
1✔
106
        this);
107

108
    _system_impl->register_mavlink_message_handler(
9✔
109
        MAVLINK_MSG_ID_VIDEO_STREAM_STATUS,
110
        [this](const mavlink_message_t& message) { process_video_stream_status(message); },
1✔
111
        this);
112

113
    _request_missing_capture_info_cookie =
9✔
114
        _system_impl->add_call_every([this]() { request_missing_capture_info(); }, 0.5);
53✔
115

116
    // TODO: use SET_INTERVAL commands instead and fall back to request commands when needed.
117
    _request_slower_call_every_cookie =
9✔
118
        _system_impl->add_call_every([this]() { request_slower(); }, 20.0);
18✔
119
    _request_faster_call_every_cookie =
9✔
120
        _system_impl->add_call_every([this]() { request_faster(); }, 5.0);
19✔
121
}
9✔
122

123
void CameraImpl::deinit()
9✔
124
{
125
    _system_impl->unregister_all_mavlink_message_handlers(this);
9✔
126

127
    _system_impl->cancel_all_param(this);
9✔
128

129
    _system_impl->remove_call_every(_request_missing_capture_info_cookie);
9✔
130
    _system_impl->remove_call_every(_request_slower_call_every_cookie);
9✔
131
    _system_impl->remove_call_every(_request_faster_call_every_cookie);
9✔
132

133
    // FIXME: There is a race condition here.
134
    // We need to wait until all call every calls are done before we go
135
    // out of scope.
136
    std::this_thread::sleep_for(std::chrono::milliseconds(100));
9✔
137

138
    std::lock_guard lock(_mutex);
9✔
139
    _storage_subscription_callbacks.clear();
9✔
140
    _mode_subscription_callbacks.clear();
9✔
141
    _capture_info_callbacks.clear();
9✔
142
    _video_stream_info_subscription_callbacks.clear();
9✔
143
    _camera_list_subscription_callbacks.clear();
9✔
144
    _subscribe_current_settings_callbacks.clear();
9✔
145
    _subscribe_possible_setting_options_callbacks.clear();
9✔
146
}
9✔
147

148
void CameraImpl::enable() {}
9✔
149
void CameraImpl::disable() {}
9✔
150

151
MavlinkCommandSender::CommandLong
152
CameraImpl::make_command_take_photo(int32_t component_id, float interval_s, float no_of_photos)
2✔
153
{
154
    MavlinkCommandSender::CommandLong cmd{};
2✔
155

156
    cmd.command = MAV_CMD_IMAGE_START_CAPTURE;
2✔
157
    cmd.params.maybe_param1 = 0.0f; // Reserved, set to 0
2✔
158
    cmd.params.maybe_param2 = interval_s;
2✔
159
    cmd.params.maybe_param3 = no_of_photos;
2✔
160
    cmd.params.maybe_param4 = get_and_increment_capture_sequence(component_id);
2✔
161
    cmd.target_component_id = fixup_component_target(component_id);
2✔
162

163
    return cmd;
2✔
164
}
165

166
MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_out(int32_t component_id)
×
167
{
168
    MavlinkCommandSender::CommandLong cmd{};
×
169
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
170
    cmd.params.maybe_param1 = static_cast<float>(ZOOM_TYPE_CONTINUOUS);
×
171
    cmd.params.maybe_param2 = -1.f;
×
172
    cmd.target_component_id = fixup_component_target(component_id);
×
173

174
    return cmd;
×
175
}
176

177
MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_in(int32_t component_id)
×
178
{
179
    MavlinkCommandSender::CommandLong cmd{};
×
180
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
181
    cmd.params.maybe_param1 = static_cast<float>(ZOOM_TYPE_CONTINUOUS);
×
182
    cmd.params.maybe_param2 = 1.f;
×
183
    cmd.target_component_id = fixup_component_target(component_id);
×
184

185
    return cmd;
×
186
}
187

188
MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_stop(int32_t component_id)
×
189
{
190
    MavlinkCommandSender::CommandLong cmd{};
×
191
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
192
    cmd.params.maybe_param1 = static_cast<float>(ZOOM_TYPE_CONTINUOUS);
×
193
    cmd.params.maybe_param2 = 0.f;
×
194
    cmd.target_component_id = fixup_component_target(component_id);
×
195

196
    return cmd;
×
197
}
198

199
MavlinkCommandSender::CommandLong
200
CameraImpl::make_command_zoom_range(int32_t component_id, float range)
×
201
{
202
    // Clip to safe range.
203
    range = std::max(0.f, std::min(range, 100.f));
×
204

205
    MavlinkCommandSender::CommandLong cmd{};
×
206
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
207
    cmd.params.maybe_param1 = static_cast<float>(ZOOM_TYPE_RANGE);
×
208
    cmd.params.maybe_param2 = range;
×
209
    cmd.target_component_id = fixup_component_target(component_id);
×
210

211
    return cmd;
×
212
}
213

214
MavlinkCommandSender::CommandLong CameraImpl::make_command_track_point(
×
215
    int32_t component_id, float point_x, float point_y, float radius)
216
{
217
    MavlinkCommandSender::CommandLong cmd{};
×
218
    cmd.command = MAV_CMD_CAMERA_TRACK_POINT;
×
219
    cmd.params.maybe_param1 = point_x;
×
220
    cmd.params.maybe_param2 = point_y;
×
221
    cmd.params.maybe_param3 = radius;
×
222
    cmd.target_component_id = fixup_component_target(component_id);
×
223

224
    return cmd;
×
225
}
226

227
MavlinkCommandSender::CommandLong CameraImpl::make_command_track_rectangle(
×
228
    int32_t component_id,
229
    float top_left_x,
230
    float top_left_y,
231
    float bottom_right_x,
232
    float bottom_right_y)
233
{
234
    MavlinkCommandSender::CommandLong cmd{};
×
235
    cmd.command = MAV_CMD_CAMERA_TRACK_RECTANGLE;
×
236
    cmd.params.maybe_param1 = top_left_x;
×
237
    cmd.params.maybe_param2 = top_left_y;
×
238
    cmd.params.maybe_param3 = bottom_right_x;
×
239
    cmd.params.maybe_param4 = bottom_right_y;
×
240
    cmd.target_component_id = fixup_component_target(component_id);
×
241

242
    return cmd;
×
243
}
244

245
MavlinkCommandSender::CommandLong CameraImpl::make_command_track_stop(int32_t component_id)
×
246
{
247
    MavlinkCommandSender::CommandLong cmd{};
×
248
    cmd.command = MAV_CMD_CAMERA_STOP_TRACKING;
×
249
    cmd.target_component_id = fixup_component_target(component_id);
×
250

251
    return cmd;
×
252
}
253

254
MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_in(int32_t component_id)
×
255
{
256
    MavlinkCommandSender::CommandLong cmd{};
×
257
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
258
    cmd.params.maybe_param1 = static_cast<float>(FOCUS_TYPE_CONTINUOUS);
×
259
    cmd.params.maybe_param2 = -1.f;
×
260
    cmd.target_component_id = fixup_component_target(component_id);
×
261

262
    return cmd;
×
263
}
264

265
MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_out(int32_t component_id)
×
266
{
267
    MavlinkCommandSender::CommandLong cmd{};
×
268
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
269
    cmd.params.maybe_param1 = static_cast<float>(FOCUS_TYPE_CONTINUOUS);
×
270
    cmd.params.maybe_param2 = 1.f;
×
271
    cmd.target_component_id = fixup_component_target(component_id);
×
272

273
    return cmd;
×
274
}
275

276
MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_stop(int32_t component_id)
×
277
{
278
    MavlinkCommandSender::CommandLong cmd{};
×
279
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
280
    cmd.params.maybe_param1 = static_cast<float>(FOCUS_TYPE_CONTINUOUS);
×
281
    cmd.params.maybe_param2 = 0.f;
×
282
    cmd.target_component_id = fixup_component_target(component_id);
×
283

284
    return cmd;
×
285
}
286

287
MavlinkCommandSender::CommandLong
288
CameraImpl::make_command_focus_range(int32_t component_id, float range)
×
289
{
290
    // Clip to safe range.
291
    range = std::max(0.f, std::min(range, 100.f));
×
292

293
    MavlinkCommandSender::CommandLong cmd{};
×
294
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
295
    cmd.params.maybe_param1 = static_cast<float>(FOCUS_TYPE_RANGE);
×
296
    cmd.params.maybe_param2 = range;
×
297
    cmd.target_component_id = fixup_component_target(component_id);
×
298

299
    return cmd;
×
300
}
301

302
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_photo(int32_t component_id)
1✔
303
{
304
    MavlinkCommandSender::CommandLong cmd_stop_photo{};
1✔
305

306
    cmd_stop_photo.command = MAV_CMD_IMAGE_STOP_CAPTURE;
1✔
307
    cmd_stop_photo.target_component_id = fixup_component_target(component_id);
1✔
308

309
    return cmd_stop_photo;
1✔
310
}
311

312
MavlinkCommandSender::CommandLong
313
CameraImpl::make_command_start_video(int32_t component_id, float capture_status_rate_hz)
×
314
{
315
    MavlinkCommandSender::CommandLong cmd_start_video{};
×
316

317
    cmd_start_video.command = MAV_CMD_VIDEO_START_CAPTURE;
×
318
    cmd_start_video.params.maybe_param1 = 0.f; // Reserved, set to 0
×
319
    cmd_start_video.params.maybe_param2 = capture_status_rate_hz;
×
320
    cmd_start_video.target_component_id = fixup_component_target(component_id);
×
321

322
    return cmd_start_video;
×
323
}
324

325
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video(int32_t component_id)
×
326
{
327
    MavlinkCommandSender::CommandLong cmd_stop_video{};
×
328

329
    cmd_stop_video.command = MAV_CMD_VIDEO_STOP_CAPTURE;
×
330
    cmd_stop_video.params.maybe_param1 = 0.f; // Reserved, set to 0
×
331
    cmd_stop_video.target_component_id = fixup_component_target(component_id);
×
332

333
    return cmd_stop_video;
×
334
}
335

336
MavlinkCommandSender::CommandLong
337
CameraImpl::make_command_set_camera_mode(int32_t component_id, float mavlink_mode)
2✔
338
{
339
    MavlinkCommandSender::CommandLong cmd_set_camera_mode{};
2✔
340

341
    cmd_set_camera_mode.command = MAV_CMD_SET_CAMERA_MODE;
2✔
342
    cmd_set_camera_mode.params.maybe_param1 = 0.0f; // Reserved, set to 0
2✔
343
    cmd_set_camera_mode.params.maybe_param2 = mavlink_mode;
2✔
344
    cmd_set_camera_mode.target_component_id = fixup_component_target(component_id);
2✔
345

346
    return cmd_set_camera_mode;
2✔
347
}
348

349
MavlinkCommandSender::CommandLong
350
CameraImpl::make_command_start_video_streaming(int32_t component_id, int32_t stream_id)
×
351
{
352
    MavlinkCommandSender::CommandLong cmd_start_video_streaming{};
×
353

354
    cmd_start_video_streaming.command = MAV_CMD_VIDEO_START_STREAMING;
×
355
    cmd_start_video_streaming.params.maybe_param1 = static_cast<float>(stream_id);
×
356
    cmd_start_video_streaming.target_component_id = fixup_component_target(component_id);
×
357

358
    return cmd_start_video_streaming;
×
359
}
360

361
MavlinkCommandSender::CommandLong
362
CameraImpl::make_command_stop_video_streaming(int32_t component_id, int32_t stream_id)
×
363
{
364
    MavlinkCommandSender::CommandLong cmd_stop_video_streaming{};
×
365

366
    cmd_stop_video_streaming.command = MAV_CMD_VIDEO_STOP_STREAMING;
×
367
    cmd_stop_video_streaming.params.maybe_param1 = static_cast<float>(stream_id);
×
368
    cmd_stop_video_streaming.target_component_id = fixup_component_target(component_id);
×
369

370
    return cmd_stop_video_streaming;
×
371
}
372

373
Camera::Result CameraImpl::take_photo(int32_t component_id)
1✔
374
{
375
    // Take 1 photo only with no interval
376
    auto cmd_take_photo = make_command_take_photo(component_id, 0.f, 1.0f);
1✔
377

378
    return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo));
1✔
379
}
380

381
Camera::Result CameraImpl::zoom_out_start(int32_t component_id)
×
382
{
383
    auto cmd = make_command_zoom_out(component_id);
×
384

385
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
386
}
387

388
Camera::Result CameraImpl::zoom_in_start(int32_t component_id)
×
389
{
390
    auto cmd = make_command_zoom_in(component_id);
×
391

392
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
393
}
394

395
Camera::Result CameraImpl::zoom_stop(int32_t component_id)
×
396
{
397
    auto cmd = make_command_zoom_stop(component_id);
×
398

399
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
400
}
401

402
Camera::Result CameraImpl::zoom_range(int32_t component_id, float range)
×
403
{
404
    auto cmd = make_command_zoom_range(component_id, range);
×
405

406
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
407
}
408

409
Camera::Result
410
CameraImpl::track_point(int32_t component_id, float point_x, float point_y, float radius)
×
411
{
412
    auto cmd = make_command_track_point(component_id, point_x, point_y, radius);
×
413

414
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
415
}
416

417
Camera::Result CameraImpl::track_rectangle(
×
418
    int32_t component_id,
419
    float top_left_x,
420
    float top_left_y,
421
    float bottom_right_x,
422
    float bottom_right_y)
423
{
424
    auto cmd = make_command_track_rectangle(
×
425
        component_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y);
426

427
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
428
}
429

430
Camera::Result CameraImpl::track_stop(int32_t component_id)
×
431
{
432
    auto cmd = make_command_track_stop(component_id);
×
433

434
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
435
}
436

437
Camera::Result CameraImpl::focus_in_start(int32_t component_id)
×
438
{
439
    auto cmd = make_command_focus_in(component_id);
×
440

441
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
442
}
443

444
Camera::Result CameraImpl::focus_out_start(int32_t component_id)
×
445
{
446
    auto cmd = make_command_focus_out(component_id);
×
447

448
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
449
}
450

451
Camera::Result CameraImpl::focus_stop(int32_t component_id)
×
452
{
453
    auto cmd = make_command_focus_stop(component_id);
×
454

455
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
456
}
457

458
Camera::Result CameraImpl::focus_range(int32_t component_id, float range)
×
459
{
460
    auto cmd = make_command_focus_range(component_id, range);
×
461

462
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
463
}
464

465
Camera::Result CameraImpl::start_photo_interval(int32_t component_id, float interval_s)
1✔
466
{
467
    auto cmd_take_photo_time_lapse = make_command_take_photo(component_id, interval_s, 0.f);
1✔
468

469
    return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo_time_lapse));
1✔
470
}
471

472
Camera::Result CameraImpl::stop_photo_interval(int32_t component_id)
1✔
473
{
474
    auto cmd_stop_photo_interval = make_command_stop_photo(component_id);
1✔
475

476
    return camera_result_from_command_result(_system_impl->send_command(cmd_stop_photo_interval));
1✔
477
}
478

479
Camera::Result CameraImpl::start_video(int32_t component_id)
×
480
{
481
    // Capture status rate is not set
482
    auto cmd_start_video = make_command_start_video(component_id, 0.f);
×
483

484
    return camera_result_from_command_result(_system_impl->send_command(cmd_start_video));
×
485
}
486

487
Camera::Result CameraImpl::stop_video(int32_t component_id)
×
488
{
489
    auto cmd_stop_video = make_command_stop_video(component_id);
×
490

491
    return camera_result_from_command_result(_system_impl->send_command(cmd_stop_video));
×
492
}
493

494
void CameraImpl::zoom_in_start_async(int32_t component_id, const Camera::ResultCallback& callback)
×
495
{
496
    auto cmd = make_command_zoom_in(component_id);
×
497

498
    _system_impl->send_command_async(
×
499
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
500
            receive_command_result(result, callback);
×
501
        });
×
502
}
×
503

504
void CameraImpl::zoom_out_start_async(int32_t component_id, const Camera::ResultCallback& callback)
×
505
{
506
    auto cmd = make_command_zoom_out(component_id);
×
507

508
    _system_impl->send_command_async(
×
509
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
510
            receive_command_result(result, callback);
×
511
        });
×
512
}
×
513

514
void CameraImpl::zoom_stop_async(int32_t component_id, const Camera::ResultCallback& callback)
×
515
{
516
    auto cmd = make_command_zoom_stop(component_id);
×
517

518
    _system_impl->send_command_async(
×
519
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
520
            receive_command_result(result, callback);
×
521
        });
×
522
}
×
523

524
void CameraImpl::zoom_range_async(
×
525
    int32_t component_id, float range, const Camera::ResultCallback& callback)
526
{
527
    auto cmd = make_command_zoom_range(component_id, range);
×
528

529
    _system_impl->send_command_async(
×
530
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
531
            receive_command_result(result, callback);
×
532
        });
×
533
}
×
534

535
void CameraImpl::track_point_async(
×
536
    int32_t component_id,
537
    float point_x,
538
    float point_y,
539
    float radius,
540
    const Camera::ResultCallback& callback)
541
{
542
    auto cmd = make_command_track_point(component_id, point_x, point_y, radius);
×
543

544
    _system_impl->send_command_async(
×
545
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
546
            receive_command_result(result, callback);
×
547
        });
×
548
}
×
549

550
void CameraImpl::track_rectangle_async(
×
551
    int32_t component_id,
552
    float top_left_x,
553
    float top_left_y,
554
    float bottom_right_x,
555
    float bottom_right_y,
556
    const Camera::ResultCallback& callback)
557
{
558
    auto cmd = make_command_track_rectangle(
×
559
        component_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y);
560

561
    _system_impl->send_command_async(
×
562
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
563
            receive_command_result(result, callback);
×
564
        });
×
565
}
×
566

567
void CameraImpl::track_stop_async(int32_t component_id, const Camera::ResultCallback& callback)
×
568
{
569
    auto cmd = make_command_track_stop(component_id);
×
570

571
    _system_impl->send_command_async(
×
572
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
573
            receive_command_result(result, callback);
×
574
        });
×
575
}
×
576

577
void CameraImpl::focus_in_start_async(int32_t component_id, const Camera::ResultCallback& callback)
×
578
{
579
    auto cmd = make_command_focus_in(component_id);
×
580

581
    _system_impl->send_command_async(
×
582
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
583
            receive_command_result(result, callback);
×
584
        });
×
585
}
×
586

587
void CameraImpl::focus_out_start_async(int32_t component_id, const Camera::ResultCallback& callback)
×
588
{
589
    auto cmd = make_command_focus_out(component_id);
×
590

591
    _system_impl->send_command_async(
×
592
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
593
            receive_command_result(result, callback);
×
594
        });
×
595
}
×
596

597
void CameraImpl::focus_stop_async(int32_t component_id, const Camera::ResultCallback& callback)
×
598
{
599
    auto cmd = make_command_focus_stop(component_id);
×
600

601
    _system_impl->send_command_async(
×
602
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
603
            receive_command_result(result, callback);
×
604
        });
×
605
}
×
606

607
void CameraImpl::focus_range_async(
×
608
    int32_t component_id, float range, const Camera::ResultCallback& callback)
609
{
610
    auto cmd = make_command_focus_range(component_id, range);
×
611

612
    _system_impl->send_command_async(
×
613
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
614
            receive_command_result(result, callback);
×
615
        });
×
616
}
×
617

618
void CameraImpl::take_photo_async(int32_t component_id, const Camera::ResultCallback& callback)
×
619
{
620
    // Take 1 photo only with no interval
621
    auto cmd_take_photo = make_command_take_photo(component_id, 0.f, 1.0f);
×
622

623
    _system_impl->send_command_async(
×
624
        cmd_take_photo, [this, callback](MavlinkCommandSender::Result result, float) {
×
625
            receive_command_result(result, callback);
×
626
        });
×
627
}
×
628

629
void CameraImpl::start_photo_interval_async(
×
630
    int32_t component_id, float interval_s, const Camera::ResultCallback& callback)
631
{
632
    auto cmd_take_photo_time_lapse = make_command_take_photo(component_id, interval_s, 0.f);
×
633

634
    _system_impl->send_command_async(
×
635
        cmd_take_photo_time_lapse, [this, callback](MavlinkCommandSender::Result result, float) {
×
636
            receive_command_result(result, callback);
×
637
        });
×
638
}
×
639

640
void CameraImpl::stop_photo_interval_async(
×
641
    int32_t component_id, const Camera::ResultCallback& callback)
642
{
643
    auto cmd_stop_photo_interval = make_command_stop_photo(component_id);
×
644

645
    _system_impl->send_command_async(
×
646
        cmd_stop_photo_interval, [this, callback](MavlinkCommandSender::Result result, float) {
×
647
            receive_command_result(result, callback);
×
648
        });
×
649
}
×
650

651
void CameraImpl::start_video_async(int32_t component_id, const Camera::ResultCallback& callback)
×
652
{
653
    // Capture status rate is not set
654
    auto cmd_start_video = make_command_start_video(component_id, 0.f);
×
655

656
    _system_impl->send_command_async(
×
657
        cmd_start_video, [this, callback](MavlinkCommandSender::Result result, float) {
×
658
            receive_command_result(result, callback);
×
659
        });
×
660
}
×
661

662
void CameraImpl::stop_video_async(int32_t component_id, const Camera::ResultCallback& callback)
×
663
{
664
    auto cmd_stop_video = make_command_stop_video(component_id);
×
665

666
    _system_impl->send_command_async(
×
667
        cmd_stop_video, [this, callback](MavlinkCommandSender::Result result, float) {
×
668
            receive_command_result(result, callback);
×
669
        });
×
670
}
×
671

672
Camera::CameraList CameraImpl::camera_list()
99✔
673
{
674
    std::lock_guard lock(_mutex);
99✔
675

676
    return camera_list_with_lock();
99✔
677
}
99✔
678

679
Camera::CameraList CameraImpl::camera_list_with_lock()
116✔
680
{
681
    Camera::CameraList result{};
116✔
682

683
    for (auto& potential_camera : potential_cameras_with_lock()) {
220✔
684
        if (!potential_camera->maybe_information) {
104✔
685
            continue;
×
686
        }
687
        result.cameras.push_back(potential_camera->maybe_information.value());
104✔
688
    }
116✔
689

690
    return result;
116✔
691
}
692

693
Camera::CameraListHandle
694
CameraImpl::subscribe_camera_list(const Camera::CameraListCallback& callback)
1✔
695
{
696
    std::lock_guard lock(_mutex);
1✔
697
    auto handle = _camera_list_subscription_callbacks.subscribe(callback);
1✔
698

699
    notify_camera_list_with_lock();
1✔
700

701
    return handle;
2✔
702
}
1✔
703

704
void CameraImpl::unsubscribe_camera_list(Camera::CameraListHandle handle)
1✔
705
{
706
    std::lock_guard lock(_mutex);
1✔
707
    _camera_list_subscription_callbacks.unsubscribe(handle);
1✔
708
}
1✔
709

710
void CameraImpl::notify_camera_list_with_lock()
17✔
711
{
712
    _system_impl->call_user_callback([&]() {
37✔
713
        _camera_list_subscription_callbacks.queue(
714
            camera_list_with_lock(), [this](const auto& func) { func(); });
715
    });
716
}
17✔
717

718
Camera::Result CameraImpl::start_video_streaming(int32_t component_id, int32_t stream_id)
×
719
{
720
    auto command = make_command_start_video_streaming(component_id, stream_id);
×
721

722
    return camera_result_from_command_result(_system_impl->send_command(command));
×
723
}
724

725
Camera::Result CameraImpl::stop_video_streaming(int32_t component_id, int32_t stream_id)
×
726
{
727
    auto command = make_command_stop_video_streaming(component_id, stream_id);
×
728

729
    return camera_result_from_command_result(_system_impl->send_command(command));
×
730
}
731

732
void CameraImpl::request_slower()
9✔
733
{
734
    std::lock_guard lock(_mutex);
9✔
735

736
    for (auto& camera : _potential_cameras) {
17✔
737
        _system_impl->mavlink_request_message().request(
16✔
738
            MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION,
739
            fixup_component_target(camera.component_id),
8✔
740
            nullptr);
741
    }
742
}
9✔
743

744
void CameraImpl::request_faster()
10✔
745
{
746
    std::lock_guard lock(_mutex);
10✔
747

748
    for (auto& camera : _potential_cameras) {
19✔
749
        _system_impl->mavlink_request_message().request(
18✔
750
            MAVLINK_MSG_ID_VIDEO_STREAM_STATUS,
751
            fixup_component_target(camera.component_id),
9✔
752
            nullptr);
753

754
        _system_impl->mavlink_request_message().request(
18✔
755
            MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS,
756
            fixup_component_target(camera.component_id),
9✔
757
            nullptr);
758

759
        _system_impl->mavlink_request_message().request(
18✔
760
            MAVLINK_MSG_ID_STORAGE_INFORMATION,
761
            fixup_component_target(camera.component_id),
9✔
762
            nullptr);
763

764
        _system_impl->mavlink_request_message().request(
18✔
765
            MAVLINK_MSG_ID_CAMERA_SETTINGS, fixup_component_target(camera.component_id), nullptr);
9✔
766
    }
767
}
10✔
768

769
Camera::VideoStreamInfoHandle
770
CameraImpl::subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& callback)
1✔
771
{
772
    std::lock_guard lock(_mutex);
1✔
773

774
    auto handle = _video_stream_info_subscription_callbacks.subscribe(callback);
1✔
775

776
    notify_video_stream_info_for_all_with_lock();
1✔
777

778
    return handle;
2✔
779
}
1✔
780

781
void CameraImpl::unsubscribe_video_stream_info(Camera::VideoStreamInfoHandle handle)
×
782
{
783
    std::lock_guard lock(_mutex);
×
784
    _video_stream_info_subscription_callbacks.unsubscribe(handle);
×
785
}
×
786

787
Camera::Result
788
CameraImpl::camera_result_from_command_result(const MavlinkCommandSender::Result command_result)
7✔
789
{
790
    switch (command_result) {
7✔
791
        case MavlinkCommandSender::Result::Success:
7✔
792
            return Camera::Result::Success;
7✔
793
        case MavlinkCommandSender::Result::NoSystem:
×
794
            // FALLTHROUGH
795
        case MavlinkCommandSender::Result::ConnectionError:
796
            // FALLTHROUGH
797
        case MavlinkCommandSender::Result::Busy:
798
            // FALLTHROUGH
799
        case MavlinkCommandSender::Result::Failed:
800
            return Camera::Result::Error;
×
801
        case MavlinkCommandSender::Result::Denied:
×
802
            // FALLTHROUGH
803
        case MavlinkCommandSender::Result::TemporarilyRejected:
804
            return Camera::Result::Denied;
×
805
        case MavlinkCommandSender::Result::Timeout:
×
806
            return Camera::Result::Timeout;
×
807
        case MavlinkCommandSender::Result::Unsupported:
×
808
            return Camera::Result::ActionUnsupported;
×
809
        case MavlinkCommandSender::Result::Cancelled:
×
810
        default:
811
            return Camera::Result::Unknown;
×
812
    }
813
}
814

815
Camera::Result CameraImpl::camera_result_from_parameter_result(
×
816
    const MavlinkParameterClient::Result parameter_result)
817
{
818
    switch (parameter_result) {
×
819
        case MavlinkParameterClient::Result::Success:
×
820
            return Camera::Result::Success;
×
821
        case MavlinkParameterClient::Result::Timeout:
×
822
            return Camera::Result::Timeout;
×
823
        case MavlinkParameterClient::Result::WrongType:
×
824
            // FALLTHROUGH
825
        case MavlinkParameterClient::Result::ParamNameTooLong:
826
            // FALLTHROUGH
827
        case MavlinkParameterClient::Result::NotFound:
828
            // FALLTHROUGH
829
        case MavlinkParameterClient::Result::ValueUnsupported:
830
            return Camera::Result::WrongArgument;
×
831
        case MavlinkParameterClient::Result::ConnectionError:
×
832
            // FALLTHROUGH
833
        case MavlinkParameterClient::Result::Failed:
834
            // FALLTHROUGH
835
        case MavlinkParameterClient::Result::UnknownError:
836
            return Camera::Result::Error;
×
837
        default:
×
838
            return Camera::Result::Unknown;
×
839
    }
840
}
841

842
Camera::Result CameraImpl::set_mode(int32_t component_id, const Camera::Mode mode)
2✔
843
{
844
    const float mavlink_mode = to_mavlink_camera_mode(mode);
2✔
845
    auto cmd_set_camera_mode = make_command_set_camera_mode(component_id, mavlink_mode);
2✔
846
    const auto command_result = _system_impl->send_command(cmd_set_camera_mode);
2✔
847
    const auto camera_result = camera_result_from_command_result(command_result);
2✔
848

849
    if (camera_result == Camera::Result::Success) {
2✔
850
        std::lock_guard lock(_mutex);
2✔
851
        auto maybe_potential_camera =
852
            maybe_potential_camera_for_component_id_with_lock(component_id, 0);
2✔
853
        if (maybe_potential_camera != nullptr) {
2✔
854
            save_camera_mode_with_lock(*maybe_potential_camera, mode);
2✔
855
        }
856
    }
2✔
857

858
    return camera_result;
2✔
859
}
860

861
void CameraImpl::save_camera_mode_with_lock(PotentialCamera& potential_camera, Camera::Mode mode)
11✔
862
{
863
    potential_camera.mode = mode;
11✔
864

865
    // If there is a camera definition which is the case if we are in this
866
    // function, and if CAM_MODE is defined there, then we reuse that type.
867
    // Otherwise, we hardcode it to `uint32_t`.
868

869
    // Note that it could be that the camera definition defines options
870
    // different from {PHOTO, VIDEO}, in which case the mode received from
871
    // CAMERA_SETTINGS will be wrong.
872

873
    if (!potential_camera.camera_definition) {
11✔
874
        return;
10✔
875
    }
876

877
    ParamValue value;
1✔
878
    if (potential_camera.camera_definition->get_setting("CAM_MODE", value)) {
1✔
879
        if (value.is<uint8_t>()) {
×
880
            value.set<uint8_t>(static_cast<uint8_t>(mode));
×
881
        } else if (value.is<int8_t>()) {
×
882
            value.set<int8_t>(static_cast<int8_t>(mode));
×
883
        } else if (value.is<uint16_t>()) {
×
884
            value.set<uint16_t>(static_cast<uint16_t>(mode));
×
885
        } else if (value.is<int16_t>()) {
×
886
            value.set<int16_t>(static_cast<int16_t>(mode));
×
887
        } else if (value.is<uint32_t>()) {
×
888
            value.set<uint32_t>(static_cast<uint32_t>(mode));
×
889
        } else if (value.is<int32_t>()) {
×
890
            value.set<int32_t>(static_cast<int32_t>(mode));
×
891
        } else if (value.is<uint64_t>()) {
×
892
            value.set<uint64_t>(static_cast<uint64_t>(mode));
×
893
        } else if (value.is<int64_t>()) {
×
894
            value.set<int64_t>(static_cast<int64_t>(mode));
×
895
        } else if (value.is<float>()) {
×
896
            value.set<float>(static_cast<float>(mode));
×
897
        } else if (value.is<double>()) {
×
898
            value.set<double>(static_cast<double>(mode));
×
899
        }
900
    } else {
901
        value.set<uint32_t>(static_cast<uint32_t>(mode));
1✔
902
    }
903

904
    potential_camera.camera_definition->set_setting("CAM_MODE", value);
1✔
905
    refresh_params_with_lock(potential_camera, false);
1✔
906
    notify_mode_with_lock(potential_camera);
1✔
907
}
1✔
908

909
float CameraImpl::to_mavlink_camera_mode(const Camera::Mode mode)
2✔
910
{
911
    switch (mode) {
2✔
912
        case Camera::Mode::Photo:
1✔
913
            return CAMERA_MODE_IMAGE;
1✔
914
        case Camera::Mode::Video:
1✔
915
            return CAMERA_MODE_VIDEO;
1✔
916
        default:
×
917
        case Camera::Mode::Unknown:
918
            return NAN;
×
919
    }
920
}
921

922
void CameraImpl::set_mode_async(
×
923
    int32_t component_id, const Camera::Mode mode, const Camera::ResultCallback& callback)
924
{
925
    const auto mavlink_mode = to_mavlink_camera_mode(mode);
×
926
    auto cmd_set_camera_mode = make_command_set_camera_mode(component_id, mavlink_mode);
×
927

928
    _system_impl->send_command_async(
×
929
        cmd_set_camera_mode,
930
        [this, callback, mode, component_id](MavlinkCommandSender::Result result, float progress) {
×
931
            UNUSED(progress);
×
932
            receive_set_mode_command_result(result, callback, mode, component_id);
×
933
        });
×
934
}
×
935

936
Camera::ModeHandle CameraImpl::subscribe_mode(const Camera::ModeCallback& callback)
×
937
{
938
    std::lock_guard lock(_mutex);
×
939
    auto handle = _mode_subscription_callbacks.subscribe(callback);
×
940

941
    notify_mode_for_all_with_lock();
×
942

943
    return handle;
×
944
}
×
945

946
void CameraImpl::unsubscribe_mode(Camera::ModeHandle handle)
×
947
{
948
    std::lock_guard lock(_mutex);
×
949
    _mode_subscription_callbacks.unsubscribe(handle);
×
950
}
×
951

952
Camera::StorageHandle CameraImpl::subscribe_storage(const Camera::StorageCallback& callback)
1✔
953
{
954
    std::lock_guard lock(_mutex);
1✔
955
    auto handle = _storage_subscription_callbacks.subscribe(callback);
1✔
956

957
    notify_storage_for_all_with_lock();
1✔
958

959
    return handle;
2✔
960
}
1✔
961

962
void CameraImpl::unsubscribe_storage(Camera::StorageHandle handle)
×
963
{
964
    std::lock_guard lock(_mutex);
×
965
    _storage_subscription_callbacks.unsubscribe(handle);
×
966
}
×
967

968
Camera::CaptureInfoHandle
969
CameraImpl::subscribe_capture_info(const Camera::CaptureInfoCallback& callback)
2✔
970
{
971
    std::lock_guard lock(_mutex);
2✔
972
    return _capture_info_callbacks.subscribe(callback);
2✔
973
}
2✔
974

975
void CameraImpl::unsubscribe_capture_info(Camera::CaptureInfoHandle handle)
2✔
976
{
977
    std::lock_guard lock(_mutex);
2✔
978
    _capture_info_callbacks.unsubscribe(handle);
2✔
979
}
2✔
980

981
void CameraImpl::process_heartbeat(const mavlink_message_t& message)
22✔
982
{
983
    // Check for potential camera
984
    std::lock_guard lock(_mutex);
22✔
985
    auto found =
986
        std::any_of(_potential_cameras.begin(), _potential_cameras.end(), [&](const auto& item) {
22✔
987
            return item.component_id == message.compid;
13✔
988
        });
989

990
    if (!found) {
22✔
991
        _potential_cameras.emplace_back(message.compid);
9✔
992
        check_potential_cameras_with_lock();
9✔
993
    }
994
}
22✔
995

996
void CameraImpl::check_potential_cameras_with_lock()
9✔
997
{
998
    for (auto& potential_camera : _potential_cameras) {
18✔
999
        // First step, get information if we don't already have it.
1000
        if (!potential_camera.maybe_information) {
9✔
1001
            request_camera_information(potential_camera.component_id);
9✔
1002
            potential_camera.information_requested = true;
9✔
1003
        }
1004
    }
1005
}
9✔
1006

1007
void CameraImpl::process_camera_capture_status(const mavlink_message_t& message)
13✔
1008
{
1009
    mavlink_camera_capture_status_t camera_capture_status;
1010
    mavlink_msg_camera_capture_status_decode(&message, &camera_capture_status);
13✔
1011

1012
    std::lock_guard lock(_mutex);
13✔
1013
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
13✔
1014
        message.compid, camera_capture_status.camera_device_id);
13✔
1015

1016
    if (maybe_potential_camera == nullptr) {
13✔
1017
        return;
×
1018
    }
1019

1020
    auto& camera = *maybe_potential_camera;
13✔
1021

1022
    // If image_count got smaller, consider that the storage was formatted.
1023
    if (camera_capture_status.image_count < camera.capture_status.image_count) {
13✔
1024
        LogInfo() << "Seems like storage was formatted, setting state accordingly";
×
1025
        reset_following_format_storage_with_lock(camera);
×
1026
    }
1027

1028
    camera.storage.video_on = (camera_capture_status.video_status == 1);
13✔
1029
    camera.storage.photo_interval_on =
13✔
1030
        (camera_capture_status.image_status == 2 || camera_capture_status.image_status == 3);
13✔
1031
    camera.capture_status.received_camera_capture_status = true;
13✔
1032
    camera.storage.recording_time_s =
13✔
1033
        static_cast<float>(camera_capture_status.recording_time_ms) / 1e3f;
13✔
1034

1035
    camera.capture_status.image_count = camera_capture_status.image_count;
13✔
1036

1037
    if (camera.capture_status.image_count_at_connection == -1) {
13✔
1038
        camera.capture_status.image_count_at_connection = camera_capture_status.image_count;
8✔
1039
    }
1040
}
13✔
1041

1042
void CameraImpl::process_storage_information(const mavlink_message_t& message)
2✔
1043
{
1044
    mavlink_storage_information_t storage_information;
1045
    mavlink_msg_storage_information_decode(&message, &storage_information);
2✔
1046

1047
    std::lock_guard lock(_mutex);
2✔
1048
    // TODO: should STORAGE_INFORMATION have a camera_device_id?
1049
    auto maybe_potential_camera =
1050
        maybe_potential_camera_for_component_id_with_lock(message.compid, 0);
2✔
1051

1052
    if (maybe_potential_camera == nullptr) {
2✔
1053
        return;
×
1054
    }
1055

1056
    auto& camera = *maybe_potential_camera;
2✔
1057

1058
    camera.storage.storage_status = storage_status_from_mavlink(storage_information.status);
2✔
1059
    camera.storage.available_storage_mib = storage_information.available_capacity;
2✔
1060
    camera.storage.used_storage_mib = storage_information.used_capacity;
2✔
1061
    camera.storage.total_storage_mib = storage_information.total_capacity;
2✔
1062
    camera.storage.storage_id = storage_information.storage_id;
2✔
1063
    camera.storage.storage_type = storage_type_from_mavlink(storage_information.type);
2✔
1064
    camera.received_storage = true;
2✔
1065

1066
    notify_storage_with_lock(camera);
2✔
1067
}
2✔
1068

1069
Camera::Storage::StorageStatus CameraImpl::storage_status_from_mavlink(const int storage_status)
2✔
1070
{
1071
    switch (storage_status) {
2✔
1072
        case STORAGE_STATUS_EMPTY:
×
1073
            return Camera::Storage::StorageStatus::NotAvailable;
×
1074
        case STORAGE_STATUS_UNFORMATTED:
×
1075
            return Camera::Storage::StorageStatus::Unformatted;
×
1076
        case STORAGE_STATUS_READY:
2✔
1077
            return Camera::Storage::StorageStatus::Formatted;
2✔
1078
            break;
1079
        case STORAGE_STATUS_NOT_SUPPORTED:
×
1080
            return Camera::Storage::StorageStatus::NotSupported;
×
1081
        default:
×
1082
            LogErr() << "Unknown storage status received.";
×
1083
            return Camera::Storage::StorageStatus::NotSupported;
×
1084
    }
1085
}
1086

1087
Camera::Storage::StorageType CameraImpl::storage_type_from_mavlink(const int storage_type)
2✔
1088
{
1089
    switch (storage_type) {
2✔
1090
        default:
×
1091
            LogErr() << "Unknown storage_type enum value: " << storage_type;
×
1092
        // FALLTHROUGH
1093
        case STORAGE_TYPE_UNKNOWN:
2✔
1094
            return mavsdk::Camera::Storage::StorageType::Unknown;
2✔
1095
        case STORAGE_TYPE_USB_STICK:
×
1096
            return mavsdk::Camera::Storage::StorageType::UsbStick;
×
1097
        case STORAGE_TYPE_SD:
×
1098
            return mavsdk::Camera::Storage::StorageType::Sd;
×
1099
        case STORAGE_TYPE_MICROSD:
×
1100
            return mavsdk::Camera::Storage::StorageType::Microsd;
×
1101
        case STORAGE_TYPE_HD:
×
1102
            return mavsdk::Camera::Storage::StorageType::Hd;
×
1103
        case STORAGE_TYPE_OTHER:
×
1104
            return mavsdk::Camera::Storage::StorageType::Other;
×
1105
    }
1106
}
1107

1108
void CameraImpl::process_camera_image_captured(const mavlink_message_t& message)
4✔
1109
{
1110
    mavlink_camera_image_captured_t image_captured;
1111
    mavlink_msg_camera_image_captured_decode(&message, &image_captured);
4✔
1112

1113
    std::lock_guard lock(_mutex);
4✔
1114
    auto maybe_potential_camera =
1115
        maybe_potential_camera_for_component_id_with_lock(message.compid, image_captured.camera_id);
4✔
1116

1117
    if (maybe_potential_camera == nullptr) {
4✔
1118
        return;
×
1119
    }
1120

1121
    auto& camera = *maybe_potential_camera;
4✔
1122

1123
    mavsdk::Quaternion quaternion{};
4✔
1124
    quaternion.w = image_captured.q[0];
4✔
1125
    quaternion.x = image_captured.q[1];
4✔
1126
    quaternion.y = image_captured.q[2];
4✔
1127
    quaternion.z = image_captured.q[3];
4✔
1128
    auto euler = to_euler_angle_from_quaternion(quaternion);
4✔
1129

1130
    Camera::CaptureInfo capture_info = {};
4✔
1131
    capture_info.component_id = camera.component_id;
4✔
1132
    capture_info.position.latitude_deg = image_captured.lat / 1e7;
4✔
1133
    capture_info.position.longitude_deg = image_captured.lon / 1e7;
4✔
1134
    capture_info.position.absolute_altitude_m = static_cast<float>(image_captured.alt) / 1e3f;
4✔
1135
    capture_info.position.relative_altitude_m =
4✔
1136
        static_cast<float>(image_captured.relative_alt) / 1e3f;
4✔
1137
    capture_info.time_utc_us = image_captured.time_utc;
4✔
1138
    capture_info.attitude_quaternion.w = image_captured.q[0];
4✔
1139
    capture_info.attitude_quaternion.x = image_captured.q[1];
4✔
1140
    capture_info.attitude_quaternion.y = image_captured.q[2];
4✔
1141
    capture_info.attitude_quaternion.z = image_captured.q[3];
4✔
1142
    capture_info.attitude_euler_angle.roll_deg = euler.roll_deg;
4✔
1143
    capture_info.attitude_euler_angle.pitch_deg = euler.pitch_deg;
4✔
1144
    capture_info.attitude_euler_angle.yaw_deg = euler.yaw_deg;
4✔
1145
    capture_info.file_url = std::string(image_captured.file_url);
4✔
1146
    capture_info.is_success = (image_captured.capture_result == 1);
4✔
1147
    capture_info.index = image_captured.image_index;
4✔
1148

1149
    camera.capture_status.photo_list.insert(
4✔
1150
        std::make_pair(image_captured.image_index, capture_info));
8✔
1151

1152
    // Notify user if a new image has been captured.
1153
    if (camera.capture_info.last_advertised_image_index < capture_info.index) {
4✔
1154
        _capture_info_callbacks.queue(
4✔
1155
            capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
4✔
1156

1157
        if (camera.capture_info.last_advertised_image_index != -1) {
4✔
1158
            // Save captured indices that have been dropped to request later, however, don't
1159
            // do it from the very beginning as there might be many photos from a previous
1160
            // time that we don't want to request.
1161
            for (int i = camera.capture_info.last_advertised_image_index + 1;
2✔
1162
                 i < capture_info.index;
2✔
1163
                 ++i) {
1164
                if (camera.capture_info.missing_image_retries.find(i) ==
×
1165
                    camera.capture_info.missing_image_retries.end()) {
×
1166
                    camera.capture_info.missing_image_retries[i] = 0;
×
1167
                }
1168
            }
1169
        }
1170

1171
        camera.capture_info.last_advertised_image_index = capture_info.index;
4✔
1172
    }
1173

1174
    else if (auto it = camera.capture_info.missing_image_retries.find(capture_info.index);
×
1175
             it != camera.capture_info.missing_image_retries.end()) {
×
1176
        _capture_info_callbacks.queue(
×
1177
            capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1178
        camera.capture_info.missing_image_retries.erase(it);
×
1179
    }
1180
}
4✔
1181

1182
void CameraImpl::request_missing_capture_info()
44✔
1183
{
1184
    std::lock_guard lock(_mutex);
44✔
1185
    for (auto& potential_camera : _potential_cameras) {
85✔
1186
        // Clean out entries once we have tried 3 times.
1187
        for (auto it = potential_camera.capture_info.missing_image_retries.begin();
41✔
1188
             it != potential_camera.capture_info.missing_image_retries.end();
41✔
1189
             /* ++it */) {
1190
            if (it->second > 3) {
×
1191
                it = potential_camera.capture_info.missing_image_retries.erase(it);
×
1192
            } else {
1193
                ++it;
×
1194
            }
1195
        }
1196

1197
        // Request a few entries, 3 each time.
1198
        for (unsigned i = 0; i < 3; ++i) {
164✔
1199
            if (!potential_camera.capture_info.missing_image_retries.empty()) {
123✔
1200
                auto it_lowest_retries = std::min_element(
×
1201
                    potential_camera.capture_info.missing_image_retries.begin(),
1202
                    potential_camera.capture_info.missing_image_retries.end());
1203
                _system_impl->mavlink_request_message().request(
×
1204
                    MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED,
1205
                    potential_camera.component_id,
×
1206
                    nullptr,
1207
                    it_lowest_retries->first);
×
1208
                it_lowest_retries->second += 1;
×
1209
            }
1210
        }
1211
    }
1212
}
44✔
1213

1214
void CameraImpl::process_camera_settings(const mavlink_message_t& message)
9✔
1215
{
1216
    mavlink_camera_settings_t camera_settings;
1217
    mavlink_msg_camera_settings_decode(&message, &camera_settings);
9✔
1218

1219
    std::lock_guard lock(_mutex);
9✔
1220
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
9✔
1221
        message.compid, camera_settings.camera_device_id);
9✔
1222

1223
    if (maybe_potential_camera == nullptr) {
9✔
1224
        return;
×
1225
    }
1226

1227
    save_camera_mode_with_lock(*maybe_potential_camera, to_camera_mode(camera_settings.mode_id));
9✔
1228
}
9✔
1229

1230
Camera::Mode CameraImpl::to_camera_mode(const uint8_t mavlink_camera_mode)
9✔
1231
{
1232
    switch (mavlink_camera_mode) {
9✔
1233
        case CAMERA_MODE_IMAGE:
9✔
1234
            return Camera::Mode::Photo;
9✔
1235
        case CAMERA_MODE_VIDEO:
×
1236
            return Camera::Mode::Video;
×
1237
        default:
×
1238
            return Camera::Mode::Unknown;
×
1239
    }
1240
}
1241

1242
void CameraImpl::process_camera_information(const mavlink_message_t& message)
9✔
1243
{
1244
    mavlink_camera_information_t camera_information;
1245
    mavlink_msg_camera_information_decode(&message, &camera_information);
9✔
1246

1247
    // Make sure all strings are zero terminated, so we don't overrun anywhere.
1248
    camera_information.vendor_name[sizeof(camera_information.vendor_name) - 1] = '\0';
9✔
1249
    camera_information.model_name[sizeof(camera_information.model_name) - 1] = '\0';
9✔
1250
    camera_information.cam_definition_uri[sizeof(camera_information.cam_definition_uri) - 1] = '\0';
9✔
1251

1252
    Camera::Information new_information{};
9✔
1253
    // TODO: Check the case for 1-6.
1254
    new_information.component_id = message.compid;
9✔
1255
    new_information.vendor_name = reinterpret_cast<char*>(camera_information.vendor_name);
9✔
1256
    new_information.model_name = reinterpret_cast<char*>(camera_information.model_name);
9✔
1257
    new_information.focal_length_mm = camera_information.focal_length;
9✔
1258
    new_information.horizontal_sensor_size_mm = camera_information.sensor_size_h;
9✔
1259
    new_information.vertical_sensor_size_mm = camera_information.sensor_size_v;
9✔
1260
    new_information.horizontal_resolution_px = camera_information.resolution_h;
9✔
1261
    new_information.vertical_resolution_px = camera_information.resolution_v;
9✔
1262

1263
    std::lock_guard lock(_mutex);
9✔
1264

1265
    auto potential_camera =
1266
        std::find_if(_potential_cameras.begin(), _potential_cameras.end(), [&](auto& item) {
9✔
1267
            return item.component_id == message.compid;
9✔
1268
        });
1269

1270
    if (potential_camera == _potential_cameras.end()) {
9✔
1271
        _potential_cameras.emplace_back(message.compid);
×
1272
        potential_camera = std::prev(_potential_cameras.end());
×
1273
    }
1274

1275
    // We need a copy of the component ID inside the information.
1276
    potential_camera->component_id = new_information.component_id;
9✔
1277
    potential_camera->maybe_information = new_information;
9✔
1278
    potential_camera->camera_definition_url = camera_information.cam_definition_uri;
9✔
1279
    potential_camera->camera_definition_version = camera_information.cam_definition_version;
9✔
1280
    check_camera_definition_with_lock(*potential_camera);
9✔
1281
}
9✔
1282

1283
void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_camera)
9✔
1284
{
1285
    const std::string url = potential_camera.camera_definition_url;
9✔
1286

1287
    if (potential_camera.camera_definition_url.empty()) {
9✔
1288
        potential_camera.camera_definition_result = Camera::Result::Unavailable;
7✔
1289
        notify_camera_list_with_lock();
7✔
1290
    }
1291

1292
    const auto& info = potential_camera.maybe_information.value();
9✔
1293
    auto file_cache_tag = replace_non_ascii_and_whitespace(
1294
        std::string("camera_definition-") + info.model_name + "_" + info.vendor_name + "-" +
18✔
1295
        std::to_string(potential_camera.camera_definition_version) + ".xml");
27✔
1296

1297
    std::optional<std::filesystem::path> cached_file_option{};
9✔
1298
    if (_file_cache) {
9✔
1299
        cached_file_option = _file_cache->access(file_cache_tag);
9✔
1300
    }
1301

1302
    if (cached_file_option) {
9✔
1303
        LogInfo() << "Using cached file " << cached_file_option.value();
1✔
1304
        load_camera_definition_with_lock(potential_camera, cached_file_option.value());
1✔
1305
        potential_camera.is_fetching_camera_definition = false;
1✔
1306
        potential_camera.camera_definition_result = Camera::Result::Success;
1✔
1307
        notify_camera_list_with_lock();
1✔
1308

1309
    } else {
1310
        potential_camera.is_fetching_camera_definition = true;
8✔
1311

1312
        if (url.empty()) {
8✔
1313
            LogInfo() << "No camera definition URL available";
7✔
1314
            potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported;
7✔
1315
            notify_camera_list_with_lock();
7✔
1316

1317
        } else if (starts_with(url, "http://") || starts_with(url, "https://")) {
1✔
1318
#if BUILD_WITHOUT_CURL == 1
1319
            potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported;
1320
            notify_camera_list_with_lock();
1321
#else
1322
            if (_http_loader == nullptr) {
×
1323
                _http_loader = std::make_unique<HttpLoader>();
×
1324
            }
1325
            LogInfo() << "Downloading camera definition from: " << url;
×
1326

1327
            auto component_id = potential_camera.component_id;
×
1328

1329
            auto download_path = _tmp_download_path / file_cache_tag;
×
1330

1331
            _http_loader->download_async(
×
1332
                url,
1333
                download_path.string(),
×
1334
                [download_path, file_cache_tag, component_id, this](
×
1335
                    int progress, HttpStatus status, CURLcode curl_code) mutable {
×
1336
                    // TODO: check if we still exist
1337
                    LogDebug() << "Download progress: " << progress
×
1338
                               << ", status: " << static_cast<int>(status)
×
1339
                               << ", curl_code: " << std::to_string(curl_code);
×
1340

1341
                    std::lock_guard lock(_mutex);
×
1342
                    auto maybe_potential_camera =
1343
                        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
×
1344
                    if (maybe_potential_camera == nullptr) {
×
1345
                        LogErr() << "Failed to find camera.";
×
1346
                    }
1347

1348
                    if (status == HttpStatus::Error) {
×
1349
                        LogErr() << "File download failed with result "
×
1350
                                 << std::to_string(curl_code);
×
1351
                        maybe_potential_camera->is_fetching_camera_definition = false;
×
1352
                        maybe_potential_camera->camera_definition_result = Camera::Result::Error;
×
1353
                        notify_camera_list_with_lock();
×
1354

1355
                    } else if (status == HttpStatus::Finished) {
×
1356
                        LogDebug() << "File download finished " << download_path;
×
1357
                        if (_file_cache) {
×
1358
                            // Cache the file (this will move/remove the temp file as well)
1359
                            download_path = _file_cache->insert(file_cache_tag, download_path)
×
1360
                                                .value_or(download_path);
×
1361
                            LogDebug() << "Cached path: " << download_path;
×
1362
                        }
1363
                        load_camera_definition_with_lock(*maybe_potential_camera, download_path);
×
1364
                        maybe_potential_camera->is_fetching_camera_definition = false;
×
1365
                        maybe_potential_camera->camera_definition_result = Camera::Result::Success;
×
1366
                        notify_camera_list_with_lock();
×
1367
                    }
1368
                });
×
1369
#endif
1370
        } else if (starts_with(url, "mftp://") || starts_with(url, "mavlinkftp://")) {
1✔
1371
            LogInfo() << "Download file: " << url << " using MAVLink FTP...";
1✔
1372

1373
            auto component_id = potential_camera.component_id;
1✔
1374

1375
            auto downloaded_filename = strip_prefix(strip_prefix(url, "mavlinkftp://"), "mftp://");
2✔
1376

1377
            _system_impl->mavlink_ftp_client().download_async(
3✔
1378
                downloaded_filename,
1379
                _tmp_download_path.string(),
2✔
1380
                false,
1381
                [file_cache_tag, downloaded_filename, component_id, this](
17✔
1382
                    MavlinkFtpClient::ClientResult client_result,
1383
                    MavlinkFtpClient::ProgressData progress_data) mutable {
2✔
1384
                    // TODO: check if we still exist
1385
                    if (client_result == MavlinkFtpClient::ClientResult::Next) {
17✔
1386
                        LogDebug()
16✔
1387
                            << "Mavlink FTP download progress: "
16✔
1388
                            << 100 * progress_data.bytes_transferred / progress_data.total_bytes
32✔
1389
                            << " %";
16✔
1390
                        return;
16✔
1391
                    }
1392

1393
                    // Use call_user_callback to defer callback execution and avoid deadlock
1394
                    _system_impl->call_user_callback(
3✔
1395
                        [file_cache_tag, downloaded_filename, component_id, client_result, this]() {
1396
                            std::lock_guard lock(_mutex);
1397
                            auto maybe_potential_camera =
1398
                                maybe_potential_camera_for_component_id_with_lock(component_id, 0);
1399
                            if (maybe_potential_camera == nullptr) {
1400
                                LogErr() << "Failed to find camera with ID " << component_id;
1401
                                return;
1402
                            }
1403

1404
                            if (client_result != MavlinkFtpClient::ClientResult::Success) {
1405
                                LogErr() << "File download failed with result " << client_result;
1406
                                maybe_potential_camera->is_fetching_camera_definition = false;
1407
                                maybe_potential_camera->camera_definition_result =
1408
                                    Camera::Result::Error;
1409
                                notify_camera_list_with_lock();
1410
                                return;
1411
                            }
1412

1413
                            auto downloaded_filepath = _tmp_download_path / downloaded_filename;
1414

1415
                            LogDebug() << "File download finished to " << downloaded_filepath;
1416
                            if (_file_cache) {
1417
                                // Cache the file (this will move/remove the temp file as well)
1418
                                downloaded_filepath =
1419
                                    _file_cache->insert(file_cache_tag, downloaded_filepath)
1420
                                        .value_or(downloaded_filepath);
1421
                                LogDebug() << "Cached path: " << downloaded_filepath;
1422
                            }
1423
                            load_camera_definition_with_lock(
1424
                                *maybe_potential_camera, downloaded_filepath);
1425
                            maybe_potential_camera->is_fetching_camera_definition = false;
1426
                            maybe_potential_camera->camera_definition_result =
1427
                                Camera::Result::Success;
1428
                            notify_camera_list_with_lock();
1429
                        });
1430
                });
1431
        } else {
1✔
1432
            LogErr() << "Unknown protocol for URL: " << url;
×
1433
            potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported;
×
1434
            notify_camera_list_with_lock();
×
1435
        }
1436
    }
1437
}
9✔
1438

1439
void CameraImpl::load_camera_definition_with_lock(
2✔
1440
    PotentialCamera& potential_camera, const std::filesystem::path& path)
1441
{
1442
    if (potential_camera.camera_definition == nullptr) {
2✔
1443
        potential_camera.camera_definition = std::make_unique<CameraDefinition>();
2✔
1444
    }
1445

1446
    if (!potential_camera.camera_definition->load_file(path.string())) {
2✔
1447
        LogErr() << "Failed to load camera definition: " << path;
×
1448
        // We can't keep something around that's not loaded correctly.
1449
        potential_camera.camera_definition = nullptr;
×
1450
        return;
×
1451
    }
1452

1453
    // We assume default settings initially and then load the params one by one.
1454
    // This way we can start using it straightaway.
1455
    potential_camera.camera_definition->reset_to_default_settings(true);
2✔
1456

1457
    refresh_params_with_lock(potential_camera, true);
2✔
1458
}
1459

1460
void CameraImpl::process_video_information(const mavlink_message_t& message)
1✔
1461
{
1462
    mavlink_video_stream_information_t received_video_info;
1463
    mavlink_msg_video_stream_information_decode(&message, &received_video_info);
1✔
1464

1465
    std::lock_guard lock(_mutex);
1✔
1466
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
1✔
1467
        message.compid, received_video_info.camera_device_id);
1✔
1468

1469
    if (maybe_potential_camera == nullptr) {
1✔
1470
        return;
×
1471
    }
1472

1473
    auto& camera = *maybe_potential_camera;
1✔
1474

1475
    // TODO: use stream_id and count
1476
    camera.video_stream_info.status =
1✔
1477
        (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
1✔
1478
             Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1479
             Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1480
    camera.video_stream_info.spectrum =
1✔
1481
        (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
1✔
1482
             Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1483
             Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1484

1485
    auto& video_stream_info = camera.video_stream_info.settings;
1✔
1486
    video_stream_info.frame_rate_hz = received_video_info.framerate;
1✔
1487
    video_stream_info.horizontal_resolution_pix = received_video_info.resolution_h;
1✔
1488
    video_stream_info.vertical_resolution_pix = received_video_info.resolution_v;
1✔
1489
    video_stream_info.bit_rate_b_s = received_video_info.bitrate;
1✔
1490
    video_stream_info.rotation_deg = received_video_info.rotation;
1✔
1491
    video_stream_info.horizontal_fov_deg = static_cast<float>(received_video_info.hfov);
1✔
1492
    video_stream_info.uri = received_video_info.uri;
1✔
1493
    camera.video_stream_info.stream_id = received_video_info.stream_id;
1✔
1494
    camera.received_video_stream_info = true;
1✔
1495

1496
    notify_video_stream_info_with_lock(camera);
1✔
1497
}
1✔
1498

1499
void CameraImpl::process_video_stream_status(const mavlink_message_t& message)
1✔
1500
{
1501
    mavlink_video_stream_status_t received_video_stream_status;
1502
    mavlink_msg_video_stream_status_decode(&message, &received_video_stream_status);
1✔
1503

1504
    std::lock_guard lock(_mutex);
1✔
1505
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
1✔
1506
        message.compid, received_video_stream_status.camera_device_id);
1✔
1507

1508
    if (maybe_potential_camera == nullptr) {
1✔
1509
        return;
×
1510
    }
1511

1512
    auto& camera = *maybe_potential_camera;
1✔
1513

1514
    camera.video_stream_info.status =
1✔
1515
        (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
1✔
1516
             Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1517
             Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1518
    camera.video_stream_info.spectrum =
1✔
1519
        (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
1✔
1520
             Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1521
             Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1522

1523
    auto& video_stream_info = camera.video_stream_info.settings;
1✔
1524
    video_stream_info.frame_rate_hz = received_video_stream_status.framerate;
1✔
1525
    video_stream_info.horizontal_resolution_pix = received_video_stream_status.resolution_h;
1✔
1526
    video_stream_info.vertical_resolution_pix = received_video_stream_status.resolution_v;
1✔
1527
    video_stream_info.bit_rate_b_s = received_video_stream_status.bitrate;
1✔
1528
    video_stream_info.rotation_deg = received_video_stream_status.rotation;
1✔
1529
    video_stream_info.horizontal_fov_deg = static_cast<float>(received_video_stream_status.hfov);
1✔
1530

1531
    // We only set this when we get the static information rather than just the status.
1532
    // camera.received_video_stream_info = true;
1533

1534
    notify_video_stream_info_with_lock(camera);
1✔
1535
}
1✔
1536

1537
void CameraImpl::notify_video_stream_info_for_all_with_lock()
1✔
1538
{
1539
    for (auto& camera : _potential_cameras) {
2✔
1540
        notify_video_stream_info_with_lock(camera);
1✔
1541
    }
1542
}
1✔
1543

1544
void CameraImpl::notify_video_stream_info_with_lock(PotentialCamera& camera)
3✔
1545
{
1546
    if (!camera.received_video_stream_info) {
3✔
1547
        return;
×
1548
    }
1549

1550
    _video_stream_info_subscription_callbacks.queue(
9✔
1551
        Camera::VideoStreamUpdate{camera.component_id, camera.video_stream_info},
6✔
1552
        [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1553
}
1554

1555
void CameraImpl::notify_storage_for_all_with_lock()
1✔
1556
{
1557
    for (auto& potential_camera : potential_cameras_with_lock()) {
2✔
1558
        notify_storage_with_lock(*potential_camera);
1✔
1559
    }
1✔
1560
}
1✔
1561

1562
void CameraImpl::notify_storage_with_lock(PotentialCamera& camera)
3✔
1563
{
1564
    if (!camera.received_storage) {
3✔
1565
        return;
×
1566
    }
1567

1568
    _storage_subscription_callbacks.queue(
9✔
1569
        Camera::StorageUpdate{camera.component_id, camera.storage},
6✔
1570
        [this](const auto& func) { _system_impl->call_user_callback(func); });
2✔
1571
}
1572

1573
void CameraImpl::receive_command_result(
2✔
1574
    MavlinkCommandSender::Result command_result, const Camera::ResultCallback& callback) const
1575
{
1576
    Camera::Result camera_result = camera_result_from_command_result(command_result);
2✔
1577

1578
    if (callback) {
2✔
1579
        _system_impl->call_user_callback([callback, camera_result]() { callback(camera_result); });
4✔
1580
    }
1581
}
2✔
1582

1583
void CameraImpl::receive_set_mode_command_result(
×
1584
    const MavlinkCommandSender::Result command_result,
1585
    const Camera::ResultCallback& callback,
1586
    const Camera::Mode mode,
1587
    int32_t component_id)
1588
{
1589
    Camera::Result camera_result = camera_result_from_command_result(command_result);
×
1590

1591
    if (callback) {
×
1592
        _system_impl->call_user_callback([callback, camera_result]() { callback(camera_result); });
×
1593
    }
1594

1595
    if (camera_result == Camera::Result::Success) {
×
1596
        std::lock_guard lock(_mutex);
×
1597
        auto maybe_potential_camera =
1598
            maybe_potential_camera_for_component_id_with_lock(component_id, 0);
×
1599
        if (maybe_potential_camera != nullptr) {
×
1600
            save_camera_mode_with_lock(*maybe_potential_camera, mode);
×
1601
        }
1602
    }
×
1603
}
×
1604

1605
void CameraImpl::notify_mode_for_all_with_lock()
×
1606
{
1607
    for (auto& camera : potential_cameras_with_lock()) {
×
1608
        notify_mode_with_lock(*camera);
×
1609
    }
×
1610
}
×
1611

1612
void CameraImpl::notify_mode_with_lock(PotentialCamera& camera)
1✔
1613
{
1614
    _mode_subscription_callbacks.queue(
2✔
1615
        Camera::ModeUpdate{camera.component_id, camera.mode},
1✔
1616
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1617
}
1✔
1618

1619
bool CameraImpl::get_possible_options_with_lock(
86✔
1620
    PotentialCamera& camera, const std::string& setting_id, std::vector<Camera::Option>& options)
1621
{
1622
    options.clear();
86✔
1623

1624
    if (!camera.camera_definition) {
86✔
1625
        LogWarn() << "Error: no camera definition available yet";
×
1626
        return false;
×
1627
    }
1628

1629
    std::vector<ParamValue> values;
86✔
1630
    if (!camera.camera_definition->get_possible_options(setting_id, values)) {
86✔
1631
        return false;
×
1632
    }
1633

1634
    for (const auto& value : values) {
312✔
1635
        Camera::Option option{};
226✔
1636
        option.option_id = value.get_string();
226✔
1637
        if (!camera.camera_definition->is_setting_range(setting_id)) {
226✔
1638
            get_option_str_with_lock(
88✔
1639
                camera, setting_id, option.option_id, option.option_description);
1640
        }
1641
        options.push_back(option);
226✔
1642
    }
226✔
1643

1644
    return !options.empty();
86✔
1645
}
86✔
1646

1647
Camera::Result CameraImpl::set_setting(int32_t component_id, const Camera::Setting& setting)
3✔
1648

1649
{
1650
    auto prom = std::make_shared<std::promise<Camera::Result>>();
3✔
1651
    auto ret = prom->get_future();
3✔
1652

1653
    set_setting_async(
3✔
1654
        component_id, setting, [&prom](Camera::Result result) { prom->set_value(result); });
3✔
1655

1656
    return ret.get();
3✔
1657
}
3✔
1658

1659
void CameraImpl::set_setting_async(
3✔
1660
    int32_t component_id, const Camera::Setting& setting, const Camera::ResultCallback& callback)
1661
{
1662
    set_option_async(component_id, setting.setting_id, setting.option, callback);
3✔
1663
}
3✔
1664

1665
void CameraImpl::set_option_async(
3✔
1666
    int32_t component_id,
1667
    const std::string& setting_id,
1668
    const Camera::Option& option,
1669
    const Camera::ResultCallback& callback)
1670
{
1671
    std::lock_guard lock(_mutex);
3✔
1672
    auto maybe_potential_camera =
1673
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
3✔
1674
    if (maybe_potential_camera == nullptr) {
3✔
1675
        if (callback != nullptr) {
×
1676
            _system_impl->call_user_callback(
×
1677
                [callback]() { callback(Camera::Result::CameraIdInvalid); });
1678
        }
1679
        return;
×
1680
    }
1681

1682
    auto& camera = *maybe_potential_camera;
3✔
1683

1684
    if (camera.camera_definition == nullptr) {
3✔
1685
        if (callback != nullptr) {
×
1686
            _system_impl->call_user_callback(
×
1687
                [callback]() { callback(Camera::Result::Unavailable); });
1688
        }
1689
        return;
×
1690
    }
1691

1692
    // We get it first so that we have the type of the param value.
1693
    ParamValue value;
3✔
1694

1695
    if (camera.camera_definition->is_setting_range(setting_id)) {
3✔
1696
        // TODO: Get type from minimum.
1697
        std::vector<ParamValue> all_values;
×
1698
        if (!camera.camera_definition->get_all_options(setting_id, all_values)) {
×
1699
            if (callback) {
×
1700
                LogErr() << "Could not get all options to get type for range param.";
×
1701
                _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); });
×
1702
            }
1703
            return;
×
1704
        }
1705

1706
        if (all_values.empty()) {
×
1707
            if (callback) {
×
1708
                LogErr() << "Could not get any options to get type for range param.";
×
1709
                _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); });
×
1710
            }
1711
            return;
×
1712
        }
1713
        value = all_values[0];
×
1714

1715
        // Now re-use that type. This is quite ugly, but I don't know how we could do better than
1716
        // that.
1717
        if (!value.set_as_same_type(option.option_id)) {
×
1718
            if (callback) {
×
1719
                LogErr() << "Could not set option value to given type.";
×
1720
                _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); });
×
1721
            }
1722
            return;
×
1723
        }
1724

1725
    } else {
×
1726
        if (!camera.camera_definition->get_option_value(setting_id, option.option_id, value)) {
3✔
1727
            if (callback) {
×
1728
                LogErr() << "Could not get option value.";
×
1729
                _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); });
×
1730
            }
1731
            return;
×
1732
        }
1733

1734
        std::vector<ParamValue> possible_values;
3✔
1735
        camera.camera_definition->get_possible_options(setting_id, possible_values);
3✔
1736
        bool allowed = false;
3✔
1737
        for (const auto& possible_value : possible_values) {
9✔
1738
            if (value == possible_value) {
6✔
1739
                allowed = true;
3✔
1740
            }
1741
        }
1742
        if (!allowed) {
3✔
1743
            LogErr() << "Setting " << setting_id << "(" << option.option_id << ") not allowed";
×
1744
            if (callback) {
×
1745
                _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); });
×
1746
            }
1747
            return;
×
1748
        }
1749
    }
3✔
1750

1751
    _system_impl->set_param_async(
6✔
1752
        setting_id,
1753
        value,
1754
        [this, component_id, callback, setting_id, value](MavlinkParameterClient::Result result) {
12✔
1755
            std::lock_guard lock_later(_mutex);
3✔
1756
            auto maybe_potential_camera_later =
1757
                maybe_potential_camera_for_component_id_with_lock(component_id, 0);
3✔
1758
            // We already checked these fields earlier, so we don't check again.
1759
            assert(maybe_potential_camera_later != nullptr);
3✔
1760
            assert(maybe_potential_camera_later->camera_definition != nullptr);
3✔
1761

1762
            auto& camera_later = *maybe_potential_camera_later;
3✔
1763

1764
            if (result != MavlinkParameterClient::Result::Success) {
3✔
1765
                if (callback) {
×
1766
                    _system_impl->call_user_callback([callback, result]() {
×
1767
                        callback(camera_result_from_parameter_result(result));
1768
                    });
1769
                }
1770
                return;
×
1771
            }
1772

1773
            if (!camera_later.camera_definition->set_setting(setting_id, value)) {
3✔
1774
                if (callback) {
×
1775
                    _system_impl->call_user_callback(
×
1776
                        [callback]() { callback(Camera::Result::Error); });
1777
                }
1778
                return;
×
1779
            }
1780

1781
            if (callback) {
3✔
1782
                _system_impl->call_user_callback(
6✔
1783
                    [callback]() { callback(Camera::Result::Success); });
1784
            }
1785
            refresh_params_with_lock(camera_later, false);
3✔
1786
        },
3✔
1787
        this,
1788
        camera.component_id,
3✔
1789
        true);
1790
}
3✔
1791

1792
void CameraImpl::get_setting_async(
2✔
1793
    int32_t component_id,
1794
    const Camera::Setting& setting,
1795
    const Camera::GetSettingCallback& callback)
1796
{
1797
    {
1798
        std::lock_guard lock(_mutex);
2✔
1799
        auto maybe_potential_camera =
1800
            maybe_potential_camera_for_component_id_with_lock(component_id, 0);
2✔
1801
        if (maybe_potential_camera == nullptr) {
2✔
1802
            if (callback != nullptr) {
×
1803
                _system_impl->call_user_callback(
×
1804
                    [callback]() { callback(Camera::Result::CameraIdInvalid, {}); });
1805
            }
1806
            return;
×
1807
        }
1808

1809
        auto& camera = *maybe_potential_camera;
2✔
1810

1811
        if (camera.camera_definition == nullptr) {
2✔
1812
            if (callback != nullptr) {
×
1813
                _system_impl->call_user_callback(
×
1814
                    [callback]() { callback(Camera::Result::Unavailable, {}); });
1815
            }
1816
            return;
×
1817
        }
1818
    }
2✔
1819

1820
    get_option_async(
4✔
1821
        component_id,
1822
        setting.setting_id,
2✔
1823
        [this, callback](Camera::Result result, const Camera::Option& option) {
4✔
1824
            Camera::Setting new_setting{};
2✔
1825
            new_setting.option = option;
2✔
1826
            if (callback) {
2✔
1827
                _system_impl->call_user_callback(
4✔
1828
                    [callback, result, new_setting]() { callback(result, new_setting); });
1829
            }
1830
        });
2✔
1831
}
1832

1833
std::pair<Camera::Result, Camera::Setting>
1834
CameraImpl::get_setting(int32_t component_id, const Camera::Setting& setting)
2✔
1835
{
1836
    auto prom = std::make_shared<std::promise<std::pair<Camera::Result, Camera::Setting>>>();
2✔
1837
    auto ret = prom->get_future();
2✔
1838

1839
    get_setting_async(
2✔
1840
        component_id, setting, [&prom](Camera::Result result, const Camera::Setting& new_setting) {
2✔
1841
            prom->set_value(std::make_pair<>(result, new_setting));
2✔
1842
        });
2✔
1843

1844
    return ret.get();
2✔
1845
}
2✔
1846

1847
Camera::Result
1848
CameraImpl::get_option(int32_t component_id, const std::string& setting_id, Camera::Option& option)
×
1849
{
1850
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1851
    auto ret = prom->get_future();
×
1852

1853
    get_option_async(
×
1854
        component_id,
1855
        setting_id,
1856
        [prom, &option](Camera::Result result, const Camera::Option& option_gotten) {
×
1857
            prom->set_value(result);
×
1858
            if (result == Camera::Result::Success) {
×
1859
                option = option_gotten;
×
1860
            }
1861
        });
×
1862

1863
    auto status = ret.wait_for(std::chrono::seconds(1));
×
1864

1865
    if (status == std::future_status::ready) {
×
1866
        return Camera::Result::Success;
×
1867
    } else {
1868
        return Camera::Result::Timeout;
×
1869
    }
1870
}
×
1871

1872
void CameraImpl::get_option_async(
2✔
1873
    int32_t component_id,
1874
    const std::string& setting_id,
1875
    const std::function<void(Camera::Result, const Camera::Option&)>& callback)
1876
{
1877
    std::lock_guard lock(_mutex);
2✔
1878
    auto maybe_potential_camera =
1879
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
2✔
1880
    if (maybe_potential_camera == nullptr) {
2✔
1881
        if (callback != nullptr) {
×
1882
            _system_impl->call_user_callback(
×
1883
                [callback]() { callback(Camera::Result::CameraIdInvalid, {}); });
1884
        }
1885
        return;
×
1886
    }
1887

1888
    auto& camera = *maybe_potential_camera;
2✔
1889

1890
    if (camera.camera_definition == nullptr) {
2✔
1891
        if (callback != nullptr) {
×
1892
            _system_impl->call_user_callback(
×
1893
                [callback]() { callback(Camera::Result::Unavailable, {}); });
1894
        }
1895
        return;
×
1896
    }
1897

1898
    ParamValue value;
2✔
1899
    // We should have this cached and don't need to get the param.
1900
    if (camera.camera_definition->get_setting(setting_id, value)) {
2✔
1901
        if (callback) {
2✔
1902
            Camera::Option new_option{};
2✔
1903
            new_option.option_id = value.get_string();
2✔
1904
            if (!camera.camera_definition->is_setting_range(setting_id)) {
2✔
1905
                get_option_str_with_lock(
1✔
1906
                    camera, setting_id, new_option.option_id, new_option.option_description);
1907
            }
1908
            const auto temp_callback = callback;
2✔
1909
            _system_impl->call_user_callback([temp_callback, new_option]() {
4✔
1910
                temp_callback(Camera::Result::Success, new_option);
1911
            });
1912
        }
2✔
1913
    } else {
1914
        // If this still happens, we request the param, but also complain.
1915
        LogWarn() << "Setting '" << setting_id << "' not found.";
×
1916
        if (callback) {
×
1917
            const auto temp_callback = callback;
×
1918
            _system_impl->call_user_callback(
×
1919
                [temp_callback]() { temp_callback(Camera::Result::Error, {}); });
1920
        }
×
1921
    }
1922
}
2✔
1923

1924
Camera::CurrentSettingsHandle
1925
CameraImpl::subscribe_current_settings(const Camera::CurrentSettingsCallback& callback)
1✔
1926
{
1927
    std::lock_guard lock(_mutex);
1✔
1928
    auto handle = _subscribe_current_settings_callbacks.subscribe(callback);
1✔
1929

1930
    notify_current_settings_for_all_with_lock();
1✔
1931
    return handle;
2✔
1932
}
1✔
1933

1934
void CameraImpl::unsubscribe_current_settings(Camera::CurrentSettingsHandle handle)
1✔
1935
{
1936
    std::lock_guard lock(_mutex);
1✔
1937
    _subscribe_current_settings_callbacks.unsubscribe(handle);
1✔
1938
}
1✔
1939

1940
Camera::PossibleSettingOptionsHandle CameraImpl::subscribe_possible_setting_options(
1✔
1941
    const Camera::PossibleSettingOptionsCallback& callback)
1942
{
1943
    std::lock_guard lock(_mutex);
1✔
1944
    auto handle = _subscribe_possible_setting_options_callbacks.subscribe(callback);
1✔
1945

1946
    notify_possible_setting_options_for_all_with_lock();
1✔
1947
    return handle;
2✔
1948
}
1✔
1949

1950
void CameraImpl::unsubscribe_possible_setting_options(Camera::PossibleSettingOptionsHandle handle)
×
1951
{
1952
    _subscribe_possible_setting_options_callbacks.unsubscribe(handle);
×
1953
}
×
1954

1955
void CameraImpl::notify_current_settings_for_all_with_lock()
1✔
1956
{
1957
    for (auto& potential_camera : potential_cameras_with_lock()) {
2✔
1958
        if (potential_camera->camera_definition != nullptr) {
1✔
1959
            notify_current_settings_with_lock(*potential_camera);
1✔
1960
        }
1961
    }
1✔
1962
}
1✔
1963

1964
void CameraImpl::notify_possible_setting_options_for_all_with_lock()
1✔
1965
{
1966
    for (auto& potential_camera : potential_cameras_with_lock()) {
2✔
1967
        if (potential_camera->camera_definition != nullptr) {
1✔
1968
            notify_possible_setting_options_with_lock(*potential_camera);
1✔
1969
        }
1970
    }
1✔
1971
}
1✔
1972

1973
void CameraImpl::notify_current_settings_with_lock(PotentialCamera& potential_camera)
4✔
1974
{
1975
    assert(potential_camera.camera_definition != nullptr);
4✔
1976

1977
    if (_subscribe_current_settings_callbacks.empty()) {
4✔
1978
        return;
2✔
1979
    }
1980

1981
    auto possible_setting_options = get_possible_setting_options_with_lock(potential_camera);
2✔
1982
    if (possible_setting_options.first != Camera::Result::Success) {
2✔
1983
        LogErr() << "Could not get possible settings in current options subscription.";
×
1984
        return;
×
1985
    }
1986

1987
    auto& camera = potential_camera;
2✔
1988

1989
    Camera::CurrentSettingsUpdate update{};
2✔
1990
    update.component_id = potential_camera.component_id;
2✔
1991

1992
    for (auto& possible_setting : possible_setting_options.second) {
23✔
1993
        // use the cache for this, presumably we updated it right before.
1994
        ParamValue value;
21✔
1995
        if (camera.camera_definition->get_setting(possible_setting.setting_id, value)) {
21✔
1996
            Camera::Setting setting{};
17✔
1997
            setting.setting_id = possible_setting.setting_id;
17✔
1998
            setting.is_range =
17✔
1999
                camera.camera_definition->is_setting_range(possible_setting.setting_id);
17✔
2000
            get_setting_str_with_lock(camera, setting.setting_id, setting.setting_description);
17✔
2001
            setting.option.option_id = value.get_string();
17✔
2002
            if (!camera.camera_definition->is_setting_range(possible_setting.setting_id)) {
17✔
2003
                get_option_str_with_lock(
9✔
2004
                    camera,
2005
                    setting.setting_id,
2006
                    setting.option.option_id,
2007
                    setting.option.option_description);
2008
            }
2009
            update.current_settings.push_back(setting);
17✔
2010
        }
17✔
2011
    }
21✔
2012

2013
    _subscribe_current_settings_callbacks.queue(
2✔
2014
        update, [this](const auto& func) { _system_impl->call_user_callback(func); });
2✔
2015
}
2✔
2016

2017
void CameraImpl::notify_possible_setting_options_with_lock(PotentialCamera& potential_camera)
4✔
2018
{
2019
    assert(potential_camera.camera_definition != nullptr);
4✔
2020

2021
    if (_subscribe_possible_setting_options_callbacks.empty()) {
4✔
2022
        return;
2✔
2023
    }
2024

2025
    Camera::PossibleSettingOptionsUpdate update{};
2✔
2026
    update.component_id = potential_camera.component_id;
2✔
2027

2028
    auto setting_options = get_possible_setting_options_with_lock(potential_camera);
2✔
2029
    if (setting_options.second.empty()) {
2✔
2030
        return;
×
2031
    }
2032

2033
    update.setting_options = setting_options.second;
2✔
2034

2035
    _subscribe_possible_setting_options_callbacks.queue(
2✔
2036
        update, [this](const auto& func) { _system_impl->call_user_callback(func); });
2✔
2037
}
2✔
2038

2039
std::pair<Camera::Result, std::vector<Camera::SettingOptions>>
2040
CameraImpl::get_possible_setting_options(int32_t component_id)
2✔
2041
{
2042
    std::pair<Camera::Result, std::vector<Camera::SettingOptions>> result;
2✔
2043

2044
    std::lock_guard lock(_mutex);
2✔
2045
    auto maybe_potential_camera =
2046
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
2✔
2047
    if (maybe_potential_camera == nullptr) {
2✔
2048
        result.first = Camera::Result::CameraIdInvalid;
×
2049
        return result;
×
2050
    }
2051

2052
    auto& camera = *maybe_potential_camera;
2✔
2053
    if (camera.is_fetching_camera_definition || camera.camera_definition == nullptr) {
2✔
2054
        result.first = Camera::Result::Unavailable;
×
2055
        return result;
×
2056
    }
2057

2058
    return get_possible_setting_options_with_lock(*maybe_potential_camera);
2✔
2059
}
2✔
2060

2061
std::pair<Camera::Result, std::vector<Camera::SettingOptions>>
2062
CameraImpl::get_possible_setting_options_with_lock(PotentialCamera& potential_camera)
8✔
2063
{
2064
    std::pair<Camera::Result, std::vector<Camera::SettingOptions>> result;
8✔
2065

2066
    std::unordered_map<std::string, ParamValue> possible_settings;
8✔
2067
    assert(potential_camera.camera_definition != nullptr);
8✔
2068

2069
    auto& camera = potential_camera;
8✔
2070

2071
    camera.camera_definition->get_possible_settings(possible_settings);
8✔
2072

2073
    for (auto& possible_setting : possible_settings) {
94✔
2074
        Camera::SettingOptions setting_options{};
86✔
2075
        setting_options.setting_id = possible_setting.first;
86✔
2076
        setting_options.is_range =
86✔
2077
            camera.camera_definition->is_setting_range(possible_setting.first);
86✔
2078
        get_setting_str_with_lock(
86✔
2079
            camera, setting_options.setting_id, setting_options.setting_description);
2080
        get_possible_options_with_lock(camera, possible_setting.first, setting_options.options);
86✔
2081
        result.second.push_back(setting_options);
86✔
2082
    }
86✔
2083

2084
    result.first = Camera::Result::Success;
8✔
2085
    return result;
8✔
2086
}
8✔
2087

2088
void CameraImpl::refresh_params_with_lock(PotentialCamera& potential_camera, bool initial_load)
6✔
2089
{
2090
    assert(potential_camera.camera_definition != nullptr);
6✔
2091

2092
    std::vector<std::pair<std::string, ParamValue>> params;
6✔
2093
    potential_camera.camera_definition->get_unknown_params(params);
6✔
2094

2095
    if (params.empty()) {
6✔
2096
        // We're assuming that we changed one option and this did not cause
2097
        // any other possible settings to change. However, we still would
2098
        // like to notify the current settings with this one change.
2099
        notify_current_settings_with_lock(potential_camera);
3✔
2100
        notify_possible_setting_options_with_lock(potential_camera);
3✔
2101
        return;
3✔
2102
    }
2103

2104
    auto component_id = potential_camera.component_id;
3✔
2105

2106
    unsigned count = 0;
3✔
2107
    for (const auto& param : params) {
35✔
2108
        const std::string& param_name = param.first;
32✔
2109
        const ParamValue& param_value_type = param.second;
32✔
2110
        const bool is_last = (count == params.size() - 1);
32✔
2111
        if (_debugging) {
32✔
2112
            LogDebug() << "Trying to get param: " << param_name;
×
2113
        }
2114
        _system_impl->param_sender(potential_camera.component_id, true)
64✔
2115
            ->get_param_async(
32✔
2116
                param_name,
2117
                param_value_type,
2118
                [component_id, param_name, is_last, this](
32✔
2119
                    MavlinkParameterClient::Result result, const ParamValue& value) {
96✔
2120
                    if (result != MavlinkParameterClient::Result::Success) {
32✔
2121
                        return;
32✔
2122
                    }
2123

2124
                    std::lock_guard lock_later(_mutex);
32✔
2125
                    auto maybe_potential_camera_later =
2126
                        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
32✔
2127
                    // We already checked these fields earlier, so we don't check again.
2128
                    assert(maybe_potential_camera_later != nullptr);
32✔
2129
                    assert(maybe_potential_camera_later->camera_definition != nullptr);
32✔
2130

2131
                    auto& camera_later = *maybe_potential_camera_later;
32✔
2132

2133
                    if (camera_later.camera_definition->set_setting(param_name, value)) {
32✔
2134
                        if (_debugging) {
32✔
2135
                            LogDebug() << "Got setting for " << param_name << ": " << value;
×
2136
                        }
2137
                        return;
32✔
2138
                    }
2139

2140
                    if (is_last) {
×
2141
                        notify_current_settings_with_lock(camera_later);
×
2142
                        notify_possible_setting_options_with_lock(camera_later);
×
2143
                    }
2144
                },
32✔
2145
                this);
2146

2147
        if (initial_load) {
32✔
2148
            subscribe_to_param_changes_with_lock(potential_camera, param_name, param_value_type);
26✔
2149
        }
2150
        ++count;
32✔
2151
    }
2152
}
6✔
2153

2154
void CameraImpl::subscribe_to_param_changes_with_lock(
26✔
2155
    PotentialCamera& camera, std::string param_name, const ParamValue& param_value_type)
2156
{
2157
    auto component_id = camera.component_id;
26✔
2158
    auto changed = [this, component_id, param_name](auto new_param) {
39✔
2159
        if (_debugging) {
13✔
2160
            LogDebug() << "Got changing param: " << param_name << " -> " << new_param;
×
2161
        }
2162

2163
        std::lock_guard lock_later(_mutex);
13✔
2164

2165
        auto maybe_potential_camera_later =
2166
            maybe_potential_camera_for_component_id_with_lock(component_id, 0);
13✔
2167
        // We already checked these fields earlier, so we don't check again.
2168
        assert(maybe_potential_camera_later != nullptr);
13✔
2169
        assert(maybe_potential_camera_later->camera_definition != nullptr);
13✔
2170
        auto& camera_later = *maybe_potential_camera_later;
13✔
2171

2172
        ParamValue param_value;
13✔
2173
        param_value.set<decltype(new_param)>(new_param);
13✔
2174
        camera_later.camera_definition->set_setting(param_name, param_value);
13✔
2175
    };
39✔
2176

2177
    if (param_value_type.is<uint8_t>()) {
26✔
2178
        _system_impl->param_sender(camera.component_id, true)
×
2179
            ->subscribe_param_changed<uint8_t>(param_name, changed, this);
×
2180
    } else if (param_value_type.is<uint8_t>()) {
26✔
2181
        _system_impl->param_sender(camera.component_id, true)
×
2182
            ->subscribe_param_changed<uint16_t>(param_name, changed, this);
×
2183
    } else if (param_value_type.is<uint32_t>()) {
26✔
2184
        _system_impl->param_sender(camera.component_id, true)
×
2185
            ->subscribe_param_changed<uint32_t>(param_name, changed, this);
×
2186
    } else if (param_value_type.is<uint64_t>()) {
26✔
2187
        _system_impl->param_sender(camera.component_id, true)
×
2188
            ->subscribe_param_changed<uint64_t>(param_name, changed, this);
×
2189
    } else if (param_value_type.is<int8_t>()) {
26✔
2190
        _system_impl->param_sender(camera.component_id, true)
×
2191
            ->subscribe_param_changed<int8_t>(param_name, changed, this);
×
2192
    } else if (param_value_type.is<int16_t>()) {
26✔
2193
        _system_impl->param_sender(camera.component_id, true)
×
2194
            ->subscribe_param_changed<int16_t>(param_name, changed, this);
×
2195
    } else if (param_value_type.is<int32_t>()) {
26✔
2196
        _system_impl->param_sender(camera.component_id, true)
26✔
2197
            ->subscribe_param_changed<int32_t>(param_name, changed, this);
26✔
2198
    } else if (param_value_type.is<int64_t>()) {
×
2199
        _system_impl->param_sender(camera.component_id, true)
×
2200
            ->subscribe_param_changed<int64_t>(param_name, changed, this);
×
2201
    } else if (param_value_type.is<float>()) {
×
2202
        _system_impl->param_sender(camera.component_id, true)
×
2203
            ->subscribe_param_changed<float>(param_name, changed, this);
×
2204
    } else if (param_value_type.is<double>()) {
×
2205
        _system_impl->param_sender(camera.component_id, true)
×
2206
            ->subscribe_param_changed<double>(param_name, changed, this);
×
2207
    } else if (param_value_type.is<std::string>()) {
×
2208
        _system_impl->param_sender(camera.component_id, true)
×
2209
            ->subscribe_param_changed<std::string>(param_name, changed, this);
×
2210
    } else {
2211
        LogErr() << "Unknown type for param " << param_name;
×
2212
    }
2213
}
26✔
2214

2215
bool CameraImpl::get_setting_str_with_lock(
124✔
2216
    PotentialCamera& potential_camera, const std::string& setting_id, std::string& description)
2217
{
2218
    if (potential_camera.camera_definition == nullptr) {
124✔
2219
        return false;
×
2220
    }
2221

2222
    return potential_camera.camera_definition->get_setting_str(setting_id, description);
124✔
2223
}
2224

2225
bool CameraImpl::get_option_str_with_lock(
108✔
2226
    PotentialCamera& potential_camera,
2227
    const std::string& setting_id,
2228
    const std::string& option_id,
2229
    std::string& description)
2230
{
2231
    if (potential_camera.camera_definition == nullptr) {
108✔
2232
        return false;
×
2233
    }
2234

2235
    return potential_camera.camera_definition->get_option_str(setting_id, option_id, description);
108✔
2236
}
2237

2238
void CameraImpl::request_camera_information(uint8_t component_id)
9✔
2239
{
2240
    _system_impl->mavlink_request_message().request(
18✔
2241
        MAVLINK_MSG_ID_CAMERA_INFORMATION, fixup_component_target(component_id), nullptr);
9✔
2242
}
9✔
2243

2244
Camera::Result CameraImpl::format_storage(int32_t component_id, int32_t storage_id)
1✔
2245
{
2246
    auto prom = std::make_shared<std::promise<Camera::Result>>();
1✔
2247
    auto ret = prom->get_future();
1✔
2248

2249
    format_storage_async(
1✔
2250
        component_id, storage_id, [prom](Camera::Result result) { prom->set_value(result); });
1✔
2251

2252
    return ret.get();
1✔
2253
}
1✔
2254

2255
void CameraImpl::format_storage_async(
1✔
2256
    int32_t component_id, int32_t storage_id, const Camera::ResultCallback& callback)
2257
{
2258
    MavlinkCommandSender::CommandLong cmd_format{};
1✔
2259

2260
    cmd_format.command = MAV_CMD_STORAGE_FORMAT;
1✔
2261
    cmd_format.params.maybe_param1 = static_cast<float>(storage_id); // storage ID
1✔
2262
    cmd_format.params.maybe_param2 = 1.0f; // format
1✔
2263
    cmd_format.params.maybe_param3 = 1.0f; // clear
1✔
2264
    cmd_format.target_component_id = component_id;
1✔
2265

2266
    _system_impl->send_command_async(
1✔
2267
        cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
2✔
2268
            UNUSED(progress);
1✔
2269

2270
            receive_command_result(result, [this, callback](Camera::Result camera_result) {
1✔
2271
                callback(camera_result);
1✔
2272
            });
1✔
2273
        });
1✔
2274
}
1✔
2275

2276
Camera::Result CameraImpl::reset_settings(int32_t component_id)
1✔
2277
{
2278
    auto prom = std::make_shared<std::promise<Camera::Result>>();
1✔
2279
    auto ret = prom->get_future();
1✔
2280

2281
    reset_settings_async(component_id, [prom](Camera::Result result) { prom->set_value(result); });
2✔
2282

2283
    return ret.get();
1✔
2284
}
1✔
2285

2286
void CameraImpl::reset_settings_async(int32_t component_id, const Camera::ResultCallback& callback)
1✔
2287
{
2288
    MavlinkCommandSender::CommandLong cmd_format{};
1✔
2289

2290
    cmd_format.command = MAV_CMD_RESET_CAMERA_SETTINGS;
1✔
2291
    cmd_format.params.maybe_param1 = 1.0f; // reset
1✔
2292
    cmd_format.target_component_id = component_id;
1✔
2293

2294
    _system_impl->send_command_async(
1✔
2295
        cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
2✔
2296
            UNUSED(progress);
1✔
2297

2298
            receive_command_result(result, [this, callback](Camera::Result camera_result) {
1✔
2299
                callback(camera_result);
1✔
2300
            });
1✔
2301
        });
1✔
2302
}
1✔
2303

2304
void CameraImpl::reset_following_format_storage_with_lock(PotentialCamera& camera)
×
2305
{
2306
    camera.capture_status.photo_list.clear();
×
2307
    camera.capture_status.image_count = 0;
×
2308
    camera.capture_status.image_count_at_connection = 0;
×
2309
    camera.capture_info.last_advertised_image_index = -1;
×
2310
    camera.capture_info.missing_image_retries.clear();
×
2311
}
×
2312

2313
std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>
2314
CameraImpl::list_photos(int32_t component_id, Camera::PhotosRange photos_range)
×
2315
{
2316
    std::promise<std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>> prom;
×
2317
    auto ret = prom.get_future();
×
2318

2319
    list_photos_async(
×
2320
        component_id,
2321
        photos_range,
2322
        [&prom](Camera::Result result, const std::vector<Camera::CaptureInfo>& photo_list) {
×
2323
            prom.set_value(std::make_pair(result, photo_list));
×
2324
        });
×
2325

2326
    return ret.get();
×
2327
}
×
2328

2329
void CameraImpl::list_photos_async(
×
2330
    int32_t component_id,
2331
    Camera::PhotosRange photos_range,
2332
    const Camera::ListPhotosCallback& callback)
2333
{
2334
    if (!callback) {
×
2335
        LogWarn() << "Trying to get a photo list with a null callback, ignoring...";
×
2336
        return;
×
2337
    }
2338

2339
    std::lock_guard lock(_mutex);
×
2340

2341
    auto maybe_potential_camera =
2342
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
×
2343
    if (maybe_potential_camera == nullptr) {
×
2344
        LogWarn() << "Invalid camera ID: " << component_id;
×
2345
        return;
×
2346
    }
2347
    auto& camera = *maybe_potential_camera;
×
2348

2349
    if (camera.capture_status.image_count == -1) {
×
2350
        LogErr() << "Cannot list photos: camera status has not been received yet!";
×
2351
        _system_impl->call_user_callback(
×
2352
            [callback]() { callback(Camera::Result::Error, std::vector<Camera::CaptureInfo>{}); });
2353
        return;
×
2354
    }
2355

2356
    // By default we just try to keep track of photos captured while we were connected.
2357
    // If the API user asks for all, we will start requesting all previous ones.
2358

2359
    if (camera.capture_status.photos_range == Camera::PhotosRange::SinceConnection &&
×
2360
        photos_range == Camera::PhotosRange::All) {
×
2361
        camera.capture_status.photos_range = photos_range;
×
2362

2363
        auto oldest_photo_it = std::min_element(
×
2364
            camera.capture_status.photo_list.begin(),
2365
            camera.capture_status.photo_list.end(),
2366
            [](auto& a, auto& b) { return a.first < b.first; });
×
2367

2368
        if (oldest_photo_it != camera.capture_status.photo_list.end()) {
×
2369
            for (int i = 0; i < oldest_photo_it->first; ++i) {
×
2370
                if (camera.capture_info.missing_image_retries.find(i) ==
×
2371
                    camera.capture_info.missing_image_retries.end()) {
×
2372
                    camera.capture_info.missing_image_retries[i] = 0;
×
2373
                }
2374
            }
2375
        }
2376
    }
2377

2378
    const int start_index = [&, this]() {
×
2379
        switch (photos_range) {
×
2380
            case Camera::PhotosRange::SinceConnection:
×
2381
                return camera.capture_status.image_count_at_connection;
×
2382
            case Camera::PhotosRange::All:
×
2383
            // FALLTHROUGH
2384
            default:
2385
                return 0;
×
2386
        }
2387
    }();
×
2388

2389
    std::vector<Camera::CaptureInfo> photo_list;
×
2390

2391
    for (const auto& capture_info : camera.capture_status.photo_list) {
×
2392
        if (capture_info.first >= start_index) {
×
2393
            photo_list.push_back(capture_info.second);
×
2394
        }
2395
    }
2396

2397
    _system_impl->call_user_callback(
×
2398
        [callback, photo_list]() { callback(Camera::Result::Success, photo_list); });
2399
}
×
2400

2401
std::pair<Camera::Result, Camera::Mode> CameraImpl::get_mode(int32_t component_id)
1✔
2402
{
2403
    std::pair<Camera::Result, Camera::Mode> result{};
1✔
2404

2405
    std::lock_guard lock(_mutex);
1✔
2406

2407
    auto maybe_potential_camera =
2408
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
1✔
2409
    if (maybe_potential_camera == nullptr) {
1✔
2410
        result.first = Camera::Result::CameraIdInvalid;
×
2411
    } else {
2412
        result.first = Camera::Result::Success;
1✔
2413
        result.second = maybe_potential_camera->mode;
1✔
2414
    }
2415

2416
    return result;
2✔
2417
}
1✔
2418

2419
std::pair<Camera::Result, Camera::Storage> CameraImpl::get_storage(int32_t component_id)
60✔
2420
{
2421
    std::pair<Camera::Result, Camera::Storage> result{};
60✔
2422

2423
    std::lock_guard lock(_mutex);
60✔
2424

2425
    auto maybe_potential_camera =
2426
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
60✔
2427
    if (maybe_potential_camera == nullptr) {
60✔
2428
        result.first = Camera::Result::CameraIdInvalid;
×
2429
    } else {
2430
        if (maybe_potential_camera->received_storage) {
60✔
2431
            result.first = Camera::Result::Success;
60✔
2432
            result.second = maybe_potential_camera->storage;
60✔
2433
        } else {
2434
            result.first = Camera::Result::Unavailable;
×
2435
        }
2436
    }
2437

2438
    return result;
60✔
2439
}
60✔
2440

2441
std::pair<Camera::Result, Camera::VideoStreamInfo>
2442
CameraImpl::get_video_stream_info(int32_t component_id)
×
2443
{
2444
    std::pair<Camera::Result, Camera::VideoStreamInfo> result{};
×
2445

2446
    std::lock_guard lock(_mutex);
×
2447

2448
    auto maybe_potential_camera =
2449
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
×
2450
    if (maybe_potential_camera == nullptr) {
×
2451
        result.first = Camera::Result::CameraIdInvalid;
×
2452
    } else {
2453
        result.first = Camera::Result::Success;
×
2454
        result.second = maybe_potential_camera->video_stream_info;
×
2455
    }
2456

2457
    return result;
×
2458
}
×
2459

2460
std::pair<Camera::Result, std::vector<Camera::Setting>>
2461
CameraImpl::get_current_settings(int32_t component_id)
2✔
2462
{
2463
    std::pair<Camera::Result, std::vector<Camera::Setting>> result;
2✔
2464

2465
    std::lock_guard lock(_mutex);
2✔
2466
    auto maybe_potential_camera =
2467
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
2✔
2468
    if (maybe_potential_camera == nullptr) {
2✔
2469
        result.first = Camera::Result::CameraIdInvalid;
×
2470
        return result;
×
2471
    }
2472

2473
    auto& camera = *maybe_potential_camera;
2✔
2474
    if (camera.is_fetching_camera_definition || camera.camera_definition == nullptr) {
2✔
2475
        result.first = Camera::Result::Unavailable;
×
2476
        return result;
×
2477
    }
2478

2479
    auto possible_setting_options = get_possible_setting_options_with_lock(camera);
2✔
2480
    if (possible_setting_options.first != Camera::Result::Success) {
2✔
2481
        result.first = possible_setting_options.first;
×
2482
        return result;
×
2483
    }
2484

2485
    for (auto& possible_setting : possible_setting_options.second) {
23✔
2486
        // use the cache for this, presumably we updated it right before.
2487
        ParamValue value;
21✔
2488
        if (camera.camera_definition->get_setting(possible_setting.setting_id, value)) {
21✔
2489
            Camera::Setting setting{};
21✔
2490
            setting.setting_id = possible_setting.setting_id;
21✔
2491
            setting.is_range =
21✔
2492
                camera.camera_definition->is_setting_range(possible_setting.setting_id);
21✔
2493
            get_setting_str_with_lock(camera, setting.setting_id, setting.setting_description);
21✔
2494
            setting.option.option_id = value.get_string();
21✔
2495
            if (!camera.camera_definition->is_setting_range(possible_setting.setting_id)) {
21✔
2496
                get_option_str_with_lock(
10✔
2497
                    camera,
2498
                    setting.setting_id,
2499
                    setting.option.option_id,
2500
                    setting.option.option_description);
2501
            }
2502
            result.second.push_back(setting);
21✔
2503
        }
21✔
2504
    }
21✔
2505

2506
    result.first = Camera::Result::Success;
2✔
2507
    return result;
2✔
2508
}
2✔
2509

2510
uint16_t CameraImpl::get_and_increment_capture_sequence(int32_t component_id)
2✔
2511
{
2512
    if (component_id == 0) {
2✔
2513
        // All cameras
2514
        return 0;
×
2515
    }
2516

2517
    std::lock_guard lock(_mutex);
2✔
2518

2519
    for (auto& potential_camera : _potential_cameras) {
2✔
2520
        if (potential_camera.component_id == component_id) {
2✔
2521
            return potential_camera.capture_sequence++;
2✔
2522
        }
2523
    }
2524

2525
    return 0;
×
2526
}
2✔
2527

2528
std::vector<CameraImpl::PotentialCamera*> CameraImpl::potential_cameras_with_lock()
119✔
2529
{
2530
    std::vector<CameraImpl::PotentialCamera*> result;
119✔
2531

2532
    for (auto& potential_camera : _potential_cameras) {
228✔
2533
        if (!potential_camera.maybe_information) {
109✔
2534
            continue;
2✔
2535
        }
2536
        result.push_back(&potential_camera);
107✔
2537
    }
2538

2539
    return result;
119✔
2540
}
2541

2542
CameraImpl::PotentialCamera* CameraImpl::maybe_potential_camera_for_component_id_with_lock(
153✔
2543
    uint8_t component_id, uint8_t camera_device_id)
2544
{
2545
    // Component Ids 1-6 means the camera is connected to the autopilot and the
2546
    // ID is set by the camera_device_id instead.
2547
    if (component_id == 1 && camera_device_id != 0) {
153✔
2548
        component_id = camera_device_id;
×
2549
    }
2550

2551
    const auto it = std::find_if(
153✔
2552
        _potential_cameras.begin(), _potential_cameras.end(), [&](auto& potential_camera) {
153✔
2553
            return potential_camera.component_id == component_id;
153✔
2554
        });
2555

2556
    if (it == _potential_cameras.end()) {
153✔
2557
        return nullptr;
×
2558
    }
2559

2560
    // How to get pointer from iterator?
2561
    return &(*it);
153✔
2562
}
2563

2564
uint8_t CameraImpl::fixup_component_target(uint8_t component_id)
58✔
2565
{
2566
    // Component Ids 1-6 means the camera is connected to the autopilot.
2567
    if (component_id >= 1 && component_id <= 6) {
58✔
2568
        return 1;
×
2569
    }
2570

2571
    return component_id;
58✔
2572
}
2573

2574
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2025 Coveralls, Inc