• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In
Build has been canceled!

mavlink / MAVSDK / 14787428187

02 May 2025 02:25AM UTC coverage: 44.322% (+0.1%) from 44.223%
14787428187

Pull #2542

github

web-flow
Merge ea31f2d89 into 2cf24f244
Pull Request #2542: Fixing thread sanitizer issues

221 of 312 new or added lines in 17 files covered. (70.83%)

75 existing lines in 8 files now uncovered.

14742 of 33261 relevant lines covered (44.32%)

285.15 hits per line

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

55.21
/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 <iterator>
18
#include <filesystem>
19
#include <functional>
20
#include <string>
21

22
namespace mavsdk {
23

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

111
    _request_missing_capture_info_cookie =
9✔
112
        _system_impl->add_call_every([this]() { request_missing_capture_info(); }, 0.5);
87✔
113

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

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

125
    _system_impl->cancel_all_param(this);
9✔
126

127
    std::lock_guard lock(_mutex);
9✔
128
    _system_impl->remove_call_every(_request_missing_capture_info_cookie);
9✔
129
    _system_impl->remove_call_every(_request_slower_call_every_cookie);
9✔
130
    _system_impl->remove_call_every(_request_faster_call_every_cookie);
9✔
131

132
    _storage_subscription_callbacks.clear();
9✔
133
    _mode_subscription_callbacks.clear();
9✔
134
    _capture_info_callbacks.clear();
9✔
135
    _video_stream_info_subscription_callbacks.clear();
9✔
136
    _camera_list_subscription_callbacks.clear();
9✔
137
    _subscribe_current_settings_callbacks.clear();
9✔
138
    _subscribe_possible_setting_options_callbacks.clear();
9✔
139
}
9✔
140

141
void CameraImpl::enable() {}
9✔
142
void CameraImpl::disable() {}
9✔
143

144
MavlinkCommandSender::CommandLong
145
CameraImpl::make_command_take_photo(int32_t component_id, float interval_s, float no_of_photos)
2✔
146
{
147
    MavlinkCommandSender::CommandLong cmd{};
2✔
148

149
    cmd.command = MAV_CMD_IMAGE_START_CAPTURE;
2✔
150
    cmd.params.maybe_param1 = 0.0f; // Reserved, set to 0
2✔
151
    cmd.params.maybe_param2 = interval_s;
2✔
152
    cmd.params.maybe_param3 = no_of_photos;
2✔
153
    cmd.params.maybe_param4 = get_and_increment_capture_sequence(component_id);
2✔
154
    cmd.target_component_id = fixup_component_target(component_id);
2✔
155

156
    return cmd;
2✔
157
}
158

159
MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_out(int32_t component_id)
×
160
{
161
    MavlinkCommandSender::CommandLong cmd{};
×
162
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
163
    cmd.params.maybe_param1 = static_cast<float>(ZOOM_TYPE_CONTINUOUS);
×
164
    cmd.params.maybe_param2 = -1.f;
×
165
    cmd.target_component_id = fixup_component_target(component_id);
×
166

167
    return cmd;
×
168
}
169

170
MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_in(int32_t component_id)
×
171
{
172
    MavlinkCommandSender::CommandLong cmd{};
×
173
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
174
    cmd.params.maybe_param1 = static_cast<float>(ZOOM_TYPE_CONTINUOUS);
×
175
    cmd.params.maybe_param2 = 1.f;
×
176
    cmd.target_component_id = fixup_component_target(component_id);
×
177

178
    return cmd;
×
179
}
180

181
MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_stop(int32_t component_id)
×
182
{
183
    MavlinkCommandSender::CommandLong cmd{};
×
184
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
185
    cmd.params.maybe_param1 = static_cast<float>(ZOOM_TYPE_CONTINUOUS);
×
186
    cmd.params.maybe_param2 = 0.f;
×
187
    cmd.target_component_id = fixup_component_target(component_id);
×
188

189
    return cmd;
×
190
}
191

192
MavlinkCommandSender::CommandLong
193
CameraImpl::make_command_zoom_range(int32_t component_id, float range)
×
194
{
195
    // Clip to safe range.
196
    range = std::max(0.f, std::min(range, 100.f));
×
197

198
    MavlinkCommandSender::CommandLong cmd{};
×
199
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
200
    cmd.params.maybe_param1 = static_cast<float>(ZOOM_TYPE_RANGE);
×
201
    cmd.params.maybe_param2 = range;
×
202
    cmd.target_component_id = fixup_component_target(component_id);
×
203

204
    return cmd;
×
205
}
206

207
MavlinkCommandSender::CommandLong CameraImpl::make_command_track_point(
×
208
    int32_t component_id, float point_x, float point_y, float radius)
209
{
210
    MavlinkCommandSender::CommandLong cmd{};
×
211
    cmd.command = MAV_CMD_CAMERA_TRACK_POINT;
×
212
    cmd.params.maybe_param1 = point_x;
×
213
    cmd.params.maybe_param2 = point_y;
×
214
    cmd.params.maybe_param3 = radius;
×
215
    cmd.target_component_id = fixup_component_target(component_id);
×
216

217
    return cmd;
×
218
}
219

220
MavlinkCommandSender::CommandLong CameraImpl::make_command_track_rectangle(
×
221
    int32_t component_id,
222
    float top_left_x,
223
    float top_left_y,
224
    float bottom_right_x,
225
    float bottom_right_y)
226
{
227
    MavlinkCommandSender::CommandLong cmd{};
×
228
    cmd.command = MAV_CMD_CAMERA_TRACK_RECTANGLE;
×
229
    cmd.params.maybe_param1 = top_left_x;
×
230
    cmd.params.maybe_param2 = top_left_y;
×
231
    cmd.params.maybe_param3 = bottom_right_x;
×
232
    cmd.params.maybe_param4 = bottom_right_y;
×
233
    cmd.target_component_id = fixup_component_target(component_id);
×
234

235
    return cmd;
×
236
}
237

238
MavlinkCommandSender::CommandLong CameraImpl::make_command_track_stop(int32_t component_id)
×
239
{
240
    MavlinkCommandSender::CommandLong cmd{};
×
241
    cmd.command = MAV_CMD_CAMERA_STOP_TRACKING;
×
242
    cmd.target_component_id = fixup_component_target(component_id);
×
243

244
    return cmd;
×
245
}
246

247
MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_in(int32_t component_id)
×
248
{
249
    MavlinkCommandSender::CommandLong cmd{};
×
250
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
251
    cmd.params.maybe_param1 = static_cast<float>(FOCUS_TYPE_CONTINUOUS);
×
252
    cmd.params.maybe_param2 = -1.f;
×
253
    cmd.target_component_id = fixup_component_target(component_id);
×
254

255
    return cmd;
×
256
}
257

258
MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_out(int32_t component_id)
×
259
{
260
    MavlinkCommandSender::CommandLong cmd{};
×
261
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
262
    cmd.params.maybe_param1 = static_cast<float>(FOCUS_TYPE_CONTINUOUS);
×
263
    cmd.params.maybe_param2 = 1.f;
×
264
    cmd.target_component_id = fixup_component_target(component_id);
×
265

266
    return cmd;
×
267
}
268

269
MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_stop(int32_t component_id)
×
270
{
271
    MavlinkCommandSender::CommandLong cmd{};
×
272
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
273
    cmd.params.maybe_param1 = static_cast<float>(FOCUS_TYPE_CONTINUOUS);
×
274
    cmd.params.maybe_param2 = 0.f;
×
275
    cmd.target_component_id = fixup_component_target(component_id);
×
276

277
    return cmd;
×
278
}
279

280
MavlinkCommandSender::CommandLong
281
CameraImpl::make_command_focus_range(int32_t component_id, float range)
×
282
{
283
    // Clip to safe range.
284
    range = std::max(0.f, std::min(range, 100.f));
×
285

286
    MavlinkCommandSender::CommandLong cmd{};
×
287
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
288
    cmd.params.maybe_param1 = static_cast<float>(FOCUS_TYPE_RANGE);
×
289
    cmd.params.maybe_param2 = range;
×
290
    cmd.target_component_id = fixup_component_target(component_id);
×
291

292
    return cmd;
×
293
}
294

295
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_photo(int32_t component_id)
1✔
296
{
297
    MavlinkCommandSender::CommandLong cmd_stop_photo{};
1✔
298

299
    cmd_stop_photo.command = MAV_CMD_IMAGE_STOP_CAPTURE;
1✔
300
    cmd_stop_photo.target_component_id = fixup_component_target(component_id);
1✔
301

302
    return cmd_stop_photo;
1✔
303
}
304

305
MavlinkCommandSender::CommandLong
306
CameraImpl::make_command_start_video(int32_t component_id, float capture_status_rate_hz)
×
307
{
308
    MavlinkCommandSender::CommandLong cmd_start_video{};
×
309

310
    cmd_start_video.command = MAV_CMD_VIDEO_START_CAPTURE;
×
311
    cmd_start_video.params.maybe_param1 = 0.f; // Reserved, set to 0
×
312
    cmd_start_video.params.maybe_param2 = capture_status_rate_hz;
×
313
    cmd_start_video.target_component_id = fixup_component_target(component_id);
×
314

315
    return cmd_start_video;
×
316
}
317

318
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video(int32_t component_id)
×
319
{
320
    MavlinkCommandSender::CommandLong cmd_stop_video{};
×
321

322
    cmd_stop_video.command = MAV_CMD_VIDEO_STOP_CAPTURE;
×
323
    cmd_stop_video.params.maybe_param1 = 0.f; // Reserved, set to 0
×
324
    cmd_stop_video.target_component_id = fixup_component_target(component_id);
×
325

326
    return cmd_stop_video;
×
327
}
328

329
MavlinkCommandSender::CommandLong
330
CameraImpl::make_command_set_camera_mode(int32_t component_id, float mavlink_mode)
2✔
331
{
332
    MavlinkCommandSender::CommandLong cmd_set_camera_mode{};
2✔
333

334
    cmd_set_camera_mode.command = MAV_CMD_SET_CAMERA_MODE;
2✔
335
    cmd_set_camera_mode.params.maybe_param1 = 0.0f; // Reserved, set to 0
2✔
336
    cmd_set_camera_mode.params.maybe_param2 = mavlink_mode;
2✔
337
    cmd_set_camera_mode.target_component_id = fixup_component_target(component_id);
2✔
338

339
    return cmd_set_camera_mode;
2✔
340
}
341

342
MavlinkCommandSender::CommandLong
343
CameraImpl::make_command_start_video_streaming(int32_t component_id, int32_t stream_id)
×
344
{
345
    MavlinkCommandSender::CommandLong cmd_start_video_streaming{};
×
346

347
    cmd_start_video_streaming.command = MAV_CMD_VIDEO_START_STREAMING;
×
348
    cmd_start_video_streaming.params.maybe_param1 = static_cast<float>(stream_id);
×
349
    cmd_start_video_streaming.target_component_id = fixup_component_target(component_id);
×
350

351
    return cmd_start_video_streaming;
×
352
}
353

354
MavlinkCommandSender::CommandLong
355
CameraImpl::make_command_stop_video_streaming(int32_t component_id, int32_t stream_id)
×
356
{
357
    MavlinkCommandSender::CommandLong cmd_stop_video_streaming{};
×
358

359
    cmd_stop_video_streaming.command = MAV_CMD_VIDEO_STOP_STREAMING;
×
360
    cmd_stop_video_streaming.params.maybe_param1 = static_cast<float>(stream_id);
×
361
    cmd_stop_video_streaming.target_component_id = fixup_component_target(component_id);
×
362

363
    return cmd_stop_video_streaming;
×
364
}
365

366
Camera::Result CameraImpl::take_photo(int32_t component_id)
1✔
367
{
368
    // Take 1 photo only with no interval
369
    auto cmd_take_photo = make_command_take_photo(component_id, 0.f, 1.0f);
1✔
370

371
    return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo));
1✔
372
}
373

374
Camera::Result CameraImpl::zoom_out_start(int32_t component_id)
×
375
{
376
    auto cmd = make_command_zoom_out(component_id);
×
377

378
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
379
}
380

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

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

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

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

395
Camera::Result CameraImpl::zoom_range(int32_t component_id, float range)
×
396
{
397
    auto cmd = make_command_zoom_range(component_id, range);
×
398

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

402
Camera::Result
403
CameraImpl::track_point(int32_t component_id, float point_x, float point_y, float radius)
×
404
{
405
    auto cmd = make_command_track_point(component_id, point_x, point_y, radius);
×
406

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

410
Camera::Result CameraImpl::track_rectangle(
×
411
    int32_t component_id,
412
    float top_left_x,
413
    float top_left_y,
414
    float bottom_right_x,
415
    float bottom_right_y)
416
{
417
    auto cmd = make_command_track_rectangle(
×
418
        component_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y);
419

420
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
421
}
422

423
Camera::Result CameraImpl::track_stop(int32_t component_id)
×
424
{
425
    auto cmd = make_command_track_stop(component_id);
×
426

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

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

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

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

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

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

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

451
Camera::Result CameraImpl::focus_range(int32_t component_id, float range)
×
452
{
453
    auto cmd = make_command_focus_range(component_id, range);
×
454

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

458
Camera::Result CameraImpl::start_photo_interval(int32_t component_id, float interval_s)
1✔
459
{
460
    auto cmd_take_photo_time_lapse = make_command_take_photo(component_id, interval_s, 0.f);
1✔
461

462
    return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo_time_lapse));
1✔
463
}
464

465
Camera::Result CameraImpl::stop_photo_interval(int32_t component_id)
1✔
466
{
467
    auto cmd_stop_photo_interval = make_command_stop_photo(component_id);
1✔
468

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

472
Camera::Result CameraImpl::start_video(int32_t component_id)
×
473
{
474
    // Capture status rate is not set
475
    auto cmd_start_video = make_command_start_video(component_id, 0.f);
×
476

477
    return camera_result_from_command_result(_system_impl->send_command(cmd_start_video));
×
478
}
479

480
Camera::Result CameraImpl::stop_video(int32_t component_id)
×
481
{
482
    auto cmd_stop_video = make_command_stop_video(component_id);
×
483

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

487
void CameraImpl::zoom_in_start_async(int32_t component_id, const Camera::ResultCallback& callback)
×
488
{
489
    auto cmd = make_command_zoom_in(component_id);
×
490

491
    _system_impl->send_command_async(
×
492
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
493
            receive_command_result(result, callback);
×
494
        });
×
495
}
×
496

497
void CameraImpl::zoom_out_start_async(int32_t component_id, const Camera::ResultCallback& callback)
×
498
{
499
    auto cmd = make_command_zoom_out(component_id);
×
500

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

507
void CameraImpl::zoom_stop_async(int32_t component_id, const Camera::ResultCallback& callback)
×
508
{
509
    auto cmd = make_command_zoom_stop(component_id);
×
510

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

517
void CameraImpl::zoom_range_async(
×
518
    int32_t component_id, float range, const Camera::ResultCallback& callback)
519
{
520
    auto cmd = make_command_zoom_range(component_id, range);
×
521

522
    _system_impl->send_command_async(
×
523
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
524
            receive_command_result(result, callback);
×
525
        });
×
526
}
×
527

528
void CameraImpl::track_point_async(
×
529
    int32_t component_id,
530
    float point_x,
531
    float point_y,
532
    float radius,
533
    const Camera::ResultCallback& callback)
534
{
535
    auto cmd = make_command_track_point(component_id, point_x, point_y, radius);
×
536

537
    _system_impl->send_command_async(
×
538
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
539
            receive_command_result(result, callback);
×
540
        });
×
541
}
×
542

543
void CameraImpl::track_rectangle_async(
×
544
    int32_t component_id,
545
    float top_left_x,
546
    float top_left_y,
547
    float bottom_right_x,
548
    float bottom_right_y,
549
    const Camera::ResultCallback& callback)
550
{
551
    auto cmd = make_command_track_rectangle(
×
552
        component_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y);
553

554
    _system_impl->send_command_async(
×
555
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
556
            receive_command_result(result, callback);
×
557
        });
×
558
}
×
559

560
void CameraImpl::track_stop_async(int32_t component_id, const Camera::ResultCallback& callback)
×
561
{
562
    auto cmd = make_command_track_stop(component_id);
×
563

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

570
void CameraImpl::focus_in_start_async(int32_t component_id, const Camera::ResultCallback& callback)
×
571
{
572
    auto cmd = make_command_focus_in(component_id);
×
573

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

580
void CameraImpl::focus_out_start_async(int32_t component_id, const Camera::ResultCallback& callback)
×
581
{
582
    auto cmd = make_command_focus_out(component_id);
×
583

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

590
void CameraImpl::focus_stop_async(int32_t component_id, const Camera::ResultCallback& callback)
×
591
{
592
    auto cmd = make_command_focus_stop(component_id);
×
593

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

600
void CameraImpl::focus_range_async(
×
601
    int32_t component_id, float range, const Camera::ResultCallback& callback)
602
{
603
    auto cmd = make_command_focus_range(component_id, range);
×
604

605
    _system_impl->send_command_async(
×
606
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
607
            receive_command_result(result, callback);
×
608
        });
×
609
}
×
610

611
void CameraImpl::take_photo_async(int32_t component_id, const Camera::ResultCallback& callback)
×
612
{
613
    // Take 1 photo only with no interval
614
    auto cmd_take_photo = make_command_take_photo(component_id, 0.f, 1.0f);
×
615

616
    _system_impl->send_command_async(
×
617
        cmd_take_photo, [this, callback](MavlinkCommandSender::Result result, float) {
×
618
            receive_command_result(result, callback);
×
619
        });
×
620
}
×
621

622
void CameraImpl::start_photo_interval_async(
×
623
    int32_t component_id, float interval_s, const Camera::ResultCallback& callback)
624
{
625
    auto cmd_take_photo_time_lapse = make_command_take_photo(component_id, interval_s, 0.f);
×
626

627
    _system_impl->send_command_async(
×
628
        cmd_take_photo_time_lapse, [this, callback](MavlinkCommandSender::Result result, float) {
×
629
            receive_command_result(result, callback);
×
630
        });
×
631
}
×
632

633
void CameraImpl::stop_photo_interval_async(
×
634
    int32_t component_id, const Camera::ResultCallback& callback)
635
{
636
    auto cmd_stop_photo_interval = make_command_stop_photo(component_id);
×
637

638
    _system_impl->send_command_async(
×
639
        cmd_stop_photo_interval, [this, callback](MavlinkCommandSender::Result result, float) {
×
640
            receive_command_result(result, callback);
×
641
        });
×
642
}
×
643

644
void CameraImpl::start_video_async(int32_t component_id, const Camera::ResultCallback& callback)
×
645
{
646
    // Capture status rate is not set
647
    auto cmd_start_video = make_command_start_video(component_id, 0.f);
×
648

649
    _system_impl->send_command_async(
×
650
        cmd_start_video, [this, callback](MavlinkCommandSender::Result result, float) {
×
651
            receive_command_result(result, callback);
×
652
        });
×
653
}
×
654

655
void CameraImpl::stop_video_async(int32_t component_id, const Camera::ResultCallback& callback)
×
656
{
657
    auto cmd_stop_video = make_command_stop_video(component_id);
×
658

659
    _system_impl->send_command_async(
×
660
        cmd_stop_video, [this, callback](MavlinkCommandSender::Result result, float) {
×
661
            receive_command_result(result, callback);
×
662
        });
×
663
}
×
664

665
Camera::CameraList CameraImpl::camera_list()
88✔
666
{
667
    std::lock_guard lock(_mutex);
88✔
668

669
    return camera_list_with_lock();
88✔
670
}
88✔
671

672
Camera::CameraList CameraImpl::camera_list_with_lock()
105✔
673
{
674
    Camera::CameraList result{};
105✔
675

676
    for (auto& potential_camera : potential_cameras_with_lock()) {
209✔
677
        if (!potential_camera->maybe_information) {
104✔
678
            continue;
×
679
        }
680
        result.cameras.push_back(potential_camera->maybe_information.value());
104✔
681
    }
105✔
682

683
    return result;
105✔
684
}
685

686
Camera::CameraListHandle
687
CameraImpl::subscribe_camera_list(const Camera::CameraListCallback& callback)
1✔
688
{
689
    std::lock_guard lock(_mutex);
1✔
690
    auto handle = _camera_list_subscription_callbacks.subscribe(callback);
1✔
691

692
    notify_camera_list_with_lock();
1✔
693

694
    return handle;
2✔
695
}
1✔
696

697
void CameraImpl::unsubscribe_camera_list(Camera::CameraListHandle handle)
1✔
698
{
699
    std::lock_guard lock(_mutex);
1✔
700
    _camera_list_subscription_callbacks.unsubscribe(handle);
1✔
701
}
1✔
702

703
void CameraImpl::notify_camera_list_with_lock()
17✔
704
{
705
    _system_impl->call_user_callback([&]() {
37✔
706
        _camera_list_subscription_callbacks.queue(
707
            camera_list_with_lock(), [this](const auto& func) { func(); });
708
    });
709
}
17✔
710

711
Camera::Result CameraImpl::start_video_streaming(int32_t component_id, int32_t stream_id)
×
712
{
713
    auto command = make_command_start_video_streaming(component_id, stream_id);
×
714

715
    return camera_result_from_command_result(_system_impl->send_command(command));
×
716
}
717

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

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

725
void CameraImpl::request_slower()
10✔
726
{
727
    std::lock_guard lock(_mutex);
10✔
728

729
    for (auto& camera : _potential_cameras) {
11✔
730
        _system_impl->mavlink_request_message().request(
2✔
731
            MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION,
732
            fixup_component_target(camera.component_id),
1✔
733
            nullptr);
734
    }
735
}
10✔
736

737
void CameraImpl::request_faster()
14✔
738
{
739
    std::lock_guard lock(_mutex);
14✔
740

741
    for (auto& camera : _potential_cameras) {
19✔
742
        _system_impl->mavlink_request_message().request(
10✔
743
            MAVLINK_MSG_ID_VIDEO_STREAM_STATUS,
744
            fixup_component_target(camera.component_id),
5✔
745
            nullptr);
746

747
        _system_impl->mavlink_request_message().request(
10✔
748
            MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS,
749
            fixup_component_target(camera.component_id),
5✔
750
            nullptr);
751

752
        _system_impl->mavlink_request_message().request(
10✔
753
            MAVLINK_MSG_ID_STORAGE_INFORMATION,
754
            fixup_component_target(camera.component_id),
5✔
755
            nullptr);
756

757
        _system_impl->mavlink_request_message().request(
10✔
758
            MAVLINK_MSG_ID_CAMERA_SETTINGS, fixup_component_target(camera.component_id), nullptr);
5✔
759
    }
760
}
14✔
761

762
Camera::VideoStreamInfoHandle
763
CameraImpl::subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& callback)
1✔
764
{
765
    std::lock_guard lock(_mutex);
1✔
766

767
    auto handle = _video_stream_info_subscription_callbacks.subscribe(callback);
1✔
768

769
    notify_video_stream_info_for_all_with_lock();
1✔
770

771
    return handle;
2✔
772
}
1✔
773

774
void CameraImpl::unsubscribe_video_stream_info(Camera::VideoStreamInfoHandle handle)
×
775
{
776
    std::lock_guard lock(_mutex);
×
777
    _video_stream_info_subscription_callbacks.unsubscribe(handle);
×
778
}
×
779

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

808
Camera::Result CameraImpl::camera_result_from_parameter_result(
×
809
    const MavlinkParameterClient::Result parameter_result)
810
{
811
    switch (parameter_result) {
×
812
        case MavlinkParameterClient::Result::Success:
×
813
            return Camera::Result::Success;
×
814
        case MavlinkParameterClient::Result::Timeout:
×
815
            return Camera::Result::Timeout;
×
816
        case MavlinkParameterClient::Result::WrongType:
×
817
            // FALLTHROUGH
818
        case MavlinkParameterClient::Result::ParamNameTooLong:
819
            // FALLTHROUGH
820
        case MavlinkParameterClient::Result::NotFound:
821
            // FALLTHROUGH
822
        case MavlinkParameterClient::Result::ValueUnsupported:
823
            return Camera::Result::WrongArgument;
×
824
        case MavlinkParameterClient::Result::ConnectionError:
×
825
            // FALLTHROUGH
826
        case MavlinkParameterClient::Result::Failed:
827
            // FALLTHROUGH
828
        case MavlinkParameterClient::Result::UnknownError:
829
            return Camera::Result::Error;
×
830
        default:
×
831
            return Camera::Result::Unknown;
×
832
    }
833
}
834

835
Camera::Result CameraImpl::set_mode(int32_t component_id, const Camera::Mode mode)
2✔
836
{
837
    const float mavlink_mode = to_mavlink_camera_mode(mode);
2✔
838
    auto cmd_set_camera_mode = make_command_set_camera_mode(component_id, mavlink_mode);
2✔
839
    const auto command_result = _system_impl->send_command(cmd_set_camera_mode);
2✔
840
    const auto camera_result = camera_result_from_command_result(command_result);
2✔
841

842
    if (camera_result == Camera::Result::Success) {
2✔
843
        std::lock_guard lock(_mutex);
2✔
844
        auto maybe_potential_camera =
845
            maybe_potential_camera_for_component_id_with_lock(component_id, 0);
2✔
846
        if (maybe_potential_camera != nullptr) {
2✔
847
            save_camera_mode_with_lock(*maybe_potential_camera, mode);
2✔
848
        }
849
    }
2✔
850

851
    return camera_result;
2✔
852
}
853

854
void CameraImpl::save_camera_mode_with_lock(PotentialCamera& potential_camera, Camera::Mode mode)
6✔
855
{
856
    potential_camera.mode = mode;
6✔
857

858
    // If there is a camera definition which is the case if we are in this
859
    // function, and if CAM_MODE is defined there, then we reuse that type.
860
    // Otherwise, we hardcode it to `uint32_t`.
861

862
    // Note that it could be that the camera definition defines options
863
    // different from {PHOTO, VIDEO}, in which case the mode received from
864
    // CAMERA_SETTINGS will be wrong.
865

866
    if (!potential_camera.camera_definition) {
6✔
867
        return;
6✔
868
    }
869

870
    ParamValue value;
×
871
    if (potential_camera.camera_definition->get_setting("CAM_MODE", value)) {
×
872
        if (value.is<uint8_t>()) {
×
873
            value.set<uint8_t>(static_cast<uint8_t>(mode));
×
874
        } else if (value.is<int8_t>()) {
×
875
            value.set<int8_t>(static_cast<int8_t>(mode));
×
876
        } else if (value.is<uint16_t>()) {
×
877
            value.set<uint16_t>(static_cast<uint16_t>(mode));
×
878
        } else if (value.is<int16_t>()) {
×
879
            value.set<int16_t>(static_cast<int16_t>(mode));
×
880
        } else if (value.is<uint32_t>()) {
×
881
            value.set<uint32_t>(static_cast<uint32_t>(mode));
×
882
        } else if (value.is<int32_t>()) {
×
883
            value.set<int32_t>(static_cast<int32_t>(mode));
×
884
        } else if (value.is<uint64_t>()) {
×
885
            value.set<uint64_t>(static_cast<uint64_t>(mode));
×
886
        } else if (value.is<int64_t>()) {
×
887
            value.set<int64_t>(static_cast<int64_t>(mode));
×
888
        } else if (value.is<float>()) {
×
889
            value.set<float>(static_cast<float>(mode));
×
890
        } else if (value.is<double>()) {
×
891
            value.set<double>(static_cast<double>(mode));
×
892
        }
893
    } else {
894
        value.set<uint32_t>(static_cast<uint32_t>(mode));
×
895
    }
896

897
    potential_camera.camera_definition->set_setting("CAM_MODE", value);
×
898
    refresh_params_with_lock(potential_camera, false);
×
899
    notify_mode_with_lock(potential_camera);
×
900
}
×
901

902
float CameraImpl::to_mavlink_camera_mode(const Camera::Mode mode)
2✔
903
{
904
    switch (mode) {
2✔
905
        case Camera::Mode::Photo:
1✔
906
            return CAMERA_MODE_IMAGE;
1✔
907
        case Camera::Mode::Video:
1✔
908
            return CAMERA_MODE_VIDEO;
1✔
909
        default:
×
910
        case Camera::Mode::Unknown:
911
            return NAN;
×
912
    }
913
}
914

915
void CameraImpl::set_mode_async(
×
916
    int32_t component_id, const Camera::Mode mode, const Camera::ResultCallback& callback)
917
{
918
    const auto mavlink_mode = to_mavlink_camera_mode(mode);
×
919
    auto cmd_set_camera_mode = make_command_set_camera_mode(component_id, mavlink_mode);
×
920

921
    _system_impl->send_command_async(
×
922
        cmd_set_camera_mode,
923
        [this, callback, mode, component_id](MavlinkCommandSender::Result result, float progress) {
×
924
            UNUSED(progress);
×
925
            receive_set_mode_command_result(result, callback, mode, component_id);
×
926
        });
×
927
}
×
928

929
Camera::ModeHandle CameraImpl::subscribe_mode(const Camera::ModeCallback& callback)
×
930
{
931
    std::lock_guard lock(_mutex);
×
932
    auto handle = _mode_subscription_callbacks.subscribe(callback);
×
933

934
    notify_mode_for_all_with_lock();
×
935

936
    return handle;
×
937
}
×
938

939
void CameraImpl::unsubscribe_mode(Camera::ModeHandle handle)
×
940
{
941
    std::lock_guard lock(_mutex);
×
942
    _mode_subscription_callbacks.unsubscribe(handle);
×
943
}
×
944

945
Camera::StorageHandle CameraImpl::subscribe_storage(const Camera::StorageCallback& callback)
1✔
946
{
947
    std::lock_guard lock(_mutex);
1✔
948
    auto handle = _storage_subscription_callbacks.subscribe(callback);
1✔
949

950
    notify_storage_for_all_with_lock();
1✔
951

952
    return handle;
2✔
953
}
1✔
954

955
void CameraImpl::unsubscribe_storage(Camera::StorageHandle handle)
×
956
{
957
    std::lock_guard lock(_mutex);
×
958
    _storage_subscription_callbacks.unsubscribe(handle);
×
959
}
×
960

961
Camera::CaptureInfoHandle
962
CameraImpl::subscribe_capture_info(const Camera::CaptureInfoCallback& callback)
2✔
963
{
964
    std::lock_guard lock(_mutex);
2✔
965
    return _capture_info_callbacks.subscribe(callback);
2✔
966
}
2✔
967

968
void CameraImpl::unsubscribe_capture_info(Camera::CaptureInfoHandle handle)
2✔
969
{
970
    std::lock_guard lock(_mutex);
2✔
971
    _capture_info_callbacks.unsubscribe(handle);
2✔
972
}
2✔
973

974
void CameraImpl::process_heartbeat(const mavlink_message_t& message)
35✔
975
{
976
    // Check for potential camera
977
    std::lock_guard lock(_mutex);
35✔
978
    auto found =
979
        std::any_of(_potential_cameras.begin(), _potential_cameras.end(), [&](const auto& item) {
35✔
980
            return item.component_id == message.compid;
26✔
981
        });
982

983
    if (!found) {
35✔
984
        _potential_cameras.emplace_back(message.compid);
9✔
985
        check_potential_cameras_with_lock();
9✔
986
    }
987
}
35✔
988

989
void CameraImpl::check_potential_cameras_with_lock()
9✔
990
{
991
    for (auto& potential_camera : _potential_cameras) {
18✔
992
        // First step, get information if we don't already have it.
993
        if (!potential_camera.maybe_information) {
9✔
994
            request_camera_information(potential_camera.component_id);
9✔
995
            potential_camera.information_requested = true;
9✔
996
        }
997
    }
998
}
9✔
999

1000
void CameraImpl::process_camera_capture_status(const mavlink_message_t& message)
4✔
1001
{
1002
    mavlink_camera_capture_status_t camera_capture_status;
4✔
1003
    mavlink_msg_camera_capture_status_decode(&message, &camera_capture_status);
4✔
1004

1005
    std::lock_guard lock(_mutex);
4✔
1006
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
4✔
1007
        message.compid, camera_capture_status.camera_device_id);
4✔
1008

1009
    if (maybe_potential_camera == nullptr) {
4✔
1010
        return;
×
1011
    }
1012

1013
    auto& camera = *maybe_potential_camera;
4✔
1014

1015
    // If image_count got smaller, consider that the storage was formatted.
1016
    if (camera_capture_status.image_count < camera.capture_status.image_count) {
4✔
1017
        LogInfo() << "Seems like storage was formatted, setting state accordingly";
×
1018
        reset_following_format_storage_with_lock(camera);
×
1019
    }
1020

1021
    camera.storage.video_on = (camera_capture_status.video_status == 1);
4✔
1022
    camera.storage.photo_interval_on =
4✔
1023
        (camera_capture_status.image_status == 2 || camera_capture_status.image_status == 3);
4✔
1024
    camera.capture_status.received_camera_capture_status = true;
4✔
1025
    camera.storage.recording_time_s =
4✔
1026
        static_cast<float>(camera_capture_status.recording_time_ms) / 1e3f;
4✔
1027

1028
    camera.capture_status.image_count = camera_capture_status.image_count;
4✔
1029

1030
    if (camera.capture_status.image_count_at_connection == -1) {
4✔
1031
        camera.capture_status.image_count_at_connection = camera_capture_status.image_count;
2✔
1032
    }
1033
}
4✔
1034

1035
void CameraImpl::process_storage_information(const mavlink_message_t& message)
1✔
1036
{
1037
    mavlink_storage_information_t storage_information;
1✔
1038
    mavlink_msg_storage_information_decode(&message, &storage_information);
1✔
1039

1040
    std::lock_guard lock(_mutex);
1✔
1041
    // TODO: should STORAGE_INFORMATION have a camera_device_id?
1042
    auto maybe_potential_camera =
1043
        maybe_potential_camera_for_component_id_with_lock(message.compid, 0);
1✔
1044

1045
    if (maybe_potential_camera == nullptr) {
1✔
1046
        return;
×
1047
    }
1048

1049
    auto& camera = *maybe_potential_camera;
1✔
1050

1051
    camera.storage.storage_status = storage_status_from_mavlink(storage_information.status);
1✔
1052
    camera.storage.available_storage_mib = storage_information.available_capacity;
1✔
1053
    camera.storage.used_storage_mib = storage_information.used_capacity;
1✔
1054
    camera.storage.total_storage_mib = storage_information.total_capacity;
1✔
1055
    camera.storage.storage_id = storage_information.storage_id;
1✔
1056
    camera.storage.storage_type = storage_type_from_mavlink(storage_information.type);
1✔
1057
    camera.received_storage = true;
1✔
1058

1059
    notify_storage_with_lock(camera);
1✔
1060
}
1✔
1061

1062
Camera::Storage::StorageStatus CameraImpl::storage_status_from_mavlink(const int storage_status)
1✔
1063
{
1064
    switch (storage_status) {
1✔
1065
        case STORAGE_STATUS_EMPTY:
×
1066
            return Camera::Storage::StorageStatus::NotAvailable;
×
1067
        case STORAGE_STATUS_UNFORMATTED:
×
1068
            return Camera::Storage::StorageStatus::Unformatted;
×
1069
        case STORAGE_STATUS_READY:
1✔
1070
            return Camera::Storage::StorageStatus::Formatted;
1✔
1071
            break;
1072
        case STORAGE_STATUS_NOT_SUPPORTED:
×
1073
            return Camera::Storage::StorageStatus::NotSupported;
×
1074
        default:
×
1075
            LogErr() << "Unknown storage status received.";
×
1076
            return Camera::Storage::StorageStatus::NotSupported;
×
1077
    }
1078
}
1079

1080
Camera::Storage::StorageType CameraImpl::storage_type_from_mavlink(const int storage_type)
1✔
1081
{
1082
    switch (storage_type) {
1✔
1083
        default:
×
1084
            LogErr() << "Unknown storage_type enum value: " << storage_type;
×
1085
        // FALLTHROUGH
1086
        case STORAGE_TYPE_UNKNOWN:
1✔
1087
            return mavsdk::Camera::Storage::StorageType::Unknown;
1✔
1088
        case STORAGE_TYPE_USB_STICK:
×
1089
            return mavsdk::Camera::Storage::StorageType::UsbStick;
×
1090
        case STORAGE_TYPE_SD:
×
1091
            return mavsdk::Camera::Storage::StorageType::Sd;
×
1092
        case STORAGE_TYPE_MICROSD:
×
1093
            return mavsdk::Camera::Storage::StorageType::Microsd;
×
1094
        case STORAGE_TYPE_HD:
×
1095
            return mavsdk::Camera::Storage::StorageType::Hd;
×
1096
        case STORAGE_TYPE_OTHER:
×
1097
            return mavsdk::Camera::Storage::StorageType::Other;
×
1098
    }
1099
}
1100

1101
void CameraImpl::process_camera_image_captured(const mavlink_message_t& message)
4✔
1102
{
1103
    mavlink_camera_image_captured_t image_captured;
4✔
1104
    mavlink_msg_camera_image_captured_decode(&message, &image_captured);
4✔
1105

1106
    std::lock_guard lock(_mutex);
4✔
1107
    auto maybe_potential_camera =
1108
        maybe_potential_camera_for_component_id_with_lock(message.compid, image_captured.camera_id);
4✔
1109

1110
    if (maybe_potential_camera == nullptr) {
4✔
1111
        return;
×
1112
    }
1113

1114
    auto& camera = *maybe_potential_camera;
4✔
1115

1116
    mavsdk::Quaternion quaternion{};
4✔
1117
    quaternion.w = image_captured.q[0];
4✔
1118
    quaternion.x = image_captured.q[1];
4✔
1119
    quaternion.y = image_captured.q[2];
4✔
1120
    quaternion.z = image_captured.q[3];
4✔
1121
    auto euler = to_euler_angle_from_quaternion(quaternion);
4✔
1122

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

1142
    camera.capture_status.photo_list.insert(
8✔
1143
        std::make_pair(image_captured.image_index, capture_info));
8✔
1144

1145
    // Notify user if a new image has been captured.
1146
    if (camera.capture_info.last_advertised_image_index < capture_info.index) {
4✔
1147
        _capture_info_callbacks.queue(
4✔
1148
            capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
4✔
1149

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

1164
        camera.capture_info.last_advertised_image_index = capture_info.index;
4✔
1165
    }
1166

1167
    else if (auto it = camera.capture_info.missing_image_retries.find(capture_info.index);
×
1168
             it != camera.capture_info.missing_image_retries.end()) {
×
1169
        _capture_info_callbacks.queue(
×
1170
            capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1171
        camera.capture_info.missing_image_retries.erase(it);
×
1172
    }
1173
}
4✔
1174

1175
void CameraImpl::request_missing_capture_info()
69✔
1176
{
1177
    std::lock_guard lock(_mutex);
69✔
1178
    for (auto& potential_camera : _potential_cameras) {
129✔
1179
        // Clean out entries once we have tried 3 times.
1180
        for (auto it = potential_camera.capture_info.missing_image_retries.begin();
60✔
1181
             it != potential_camera.capture_info.missing_image_retries.end();
60✔
1182
             /* ++it */) {
1183
            if (it->second > 3) {
×
1184
                it = potential_camera.capture_info.missing_image_retries.erase(it);
×
1185
            } else {
1186
                ++it;
×
1187
            }
1188
        }
1189

1190
        // Request a few entries, 3 each time.
1191
        for (unsigned i = 0; i < 3; ++i) {
240✔
1192
            if (!potential_camera.capture_info.missing_image_retries.empty()) {
180✔
1193
                auto it_lowest_retries = std::min_element(
×
1194
                    potential_camera.capture_info.missing_image_retries.begin(),
1195
                    potential_camera.capture_info.missing_image_retries.end());
1196
                _system_impl->mavlink_request_message().request(
×
1197
                    MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED,
1198
                    potential_camera.component_id,
×
1199
                    nullptr,
1200
                    it_lowest_retries->first);
×
1201
                it_lowest_retries->second += 1;
×
1202
            }
1203
        }
1204
    }
1205
}
69✔
1206

1207
void CameraImpl::process_camera_settings(const mavlink_message_t& message)
4✔
1208
{
1209
    mavlink_camera_settings_t camera_settings;
4✔
1210
    mavlink_msg_camera_settings_decode(&message, &camera_settings);
4✔
1211

1212
    std::lock_guard lock(_mutex);
4✔
1213
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
4✔
1214
        message.compid, camera_settings.camera_device_id);
4✔
1215

1216
    if (maybe_potential_camera == nullptr) {
4✔
1217
        return;
×
1218
    }
1219

1220
    save_camera_mode_with_lock(*maybe_potential_camera, to_camera_mode(camera_settings.mode_id));
4✔
1221
}
4✔
1222

1223
Camera::Mode CameraImpl::to_camera_mode(const uint8_t mavlink_camera_mode)
4✔
1224
{
1225
    switch (mavlink_camera_mode) {
4✔
1226
        case CAMERA_MODE_IMAGE:
4✔
1227
            return Camera::Mode::Photo;
4✔
1228
        case CAMERA_MODE_VIDEO:
×
1229
            return Camera::Mode::Video;
×
1230
        default:
×
1231
            return Camera::Mode::Unknown;
×
1232
    }
1233
}
1234

1235
void CameraImpl::process_camera_information(const mavlink_message_t& message)
9✔
1236
{
1237
    mavlink_camera_information_t camera_information;
9✔
1238
    mavlink_msg_camera_information_decode(&message, &camera_information);
9✔
1239

1240
    // Make sure all strings are zero terminated, so we don't overrun anywhere.
1241
    camera_information.vendor_name[sizeof(camera_information.vendor_name) - 1] = '\0';
9✔
1242
    camera_information.model_name[sizeof(camera_information.model_name) - 1] = '\0';
9✔
1243
    camera_information.cam_definition_uri[sizeof(camera_information.cam_definition_uri) - 1] = '\0';
9✔
1244

1245
    Camera::Information new_information{};
9✔
1246
    // TODO: Check the case for 1-6.
1247
    new_information.component_id = message.compid;
9✔
1248
    new_information.vendor_name = reinterpret_cast<char*>(camera_information.vendor_name);
9✔
1249
    new_information.model_name = reinterpret_cast<char*>(camera_information.model_name);
9✔
1250
    new_information.focal_length_mm = camera_information.focal_length;
9✔
1251
    new_information.horizontal_sensor_size_mm = camera_information.sensor_size_h;
9✔
1252
    new_information.vertical_sensor_size_mm = camera_information.sensor_size_v;
9✔
1253
    new_information.horizontal_resolution_px = camera_information.resolution_h;
9✔
1254
    new_information.vertical_resolution_px = camera_information.resolution_v;
9✔
1255

1256
    std::lock_guard lock(_mutex);
9✔
1257

1258
    auto potential_camera =
9✔
1259
        std::find_if(_potential_cameras.begin(), _potential_cameras.end(), [&](auto& item) {
9✔
1260
            return item.component_id == message.compid;
9✔
1261
        });
1262

1263
    if (potential_camera == _potential_cameras.end()) {
9✔
1264
        _potential_cameras.emplace_back(message.compid);
×
1265
        potential_camera = std::prev(_potential_cameras.end());
×
1266
    }
1267

1268
    // We need a copy of the component ID inside the information.
1269
    potential_camera->component_id = new_information.component_id;
9✔
1270
    potential_camera->maybe_information = new_information;
9✔
1271
    potential_camera->camera_definition_url = camera_information.cam_definition_uri;
9✔
1272
    potential_camera->camera_definition_version = camera_information.cam_definition_version;
9✔
1273
    check_camera_definition_with_lock(*potential_camera);
9✔
1274
}
9✔
1275

1276
void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_camera)
9✔
1277
{
1278
    const std::string url = potential_camera.camera_definition_url;
9✔
1279

1280
    if (potential_camera.camera_definition_url.empty()) {
9✔
1281
        potential_camera.camera_definition_result = Camera::Result::Unavailable;
7✔
1282
        notify_camera_list_with_lock();
7✔
1283
    }
1284

1285
    const auto& info = potential_camera.maybe_information.value();
9✔
1286
    auto file_cache_tag = replace_non_ascii_and_whitespace(
9✔
1287
        std::string("camera_definition-") + info.model_name + "_" + info.vendor_name + "-" +
81✔
1288
        std::to_string(potential_camera.camera_definition_version) + ".xml");
45✔
1289

1290
    std::optional<std::filesystem::path> cached_file_option{};
9✔
1291
    if (_file_cache) {
9✔
1292
        cached_file_option = _file_cache->access(file_cache_tag);
9✔
1293
    }
1294

1295
    if (cached_file_option) {
9✔
1296
        LogInfo() << "Using cached file " << cached_file_option.value();
1✔
1297
        load_camera_definition_with_lock(potential_camera, cached_file_option.value());
1✔
1298
        potential_camera.is_fetching_camera_definition = false;
1✔
1299
        potential_camera.camera_definition_result = Camera::Result::Success;
1✔
1300
        notify_camera_list_with_lock();
1✔
1301

1302
    } else {
1303
        potential_camera.is_fetching_camera_definition = true;
8✔
1304

1305
        if (url.empty()) {
8✔
1306
            LogInfo() << "No camera definition URL available";
7✔
1307
            potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported;
7✔
1308
            notify_camera_list_with_lock();
7✔
1309

1310
        } else if (starts_with(url, "http://") || starts_with(url, "https://")) {
1✔
1311
#if BUILD_WITHOUT_CURL == 1
1312
            potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported;
1313
            notify_camera_list_with_lock();
1314
#else
1315
            if (_http_loader == nullptr) {
×
1316
                _http_loader = std::make_unique<HttpLoader>();
×
1317
            }
1318
            LogInfo() << "Downloading camera definition from: " << url;
×
1319

1320
            auto component_id = potential_camera.component_id;
×
1321

1322
            auto download_path = _tmp_download_path / file_cache_tag;
×
1323

1324
            _http_loader->download_async(
×
1325
                url,
1326
                download_path.string(),
×
1327
                [download_path, file_cache_tag, component_id, this](
×
1328
                    int progress, HttpStatus status, CURLcode curl_code) mutable {
×
1329
                    // TODO: check if we still exist
1330
                    LogDebug() << "Download progress: " << progress
×
1331
                               << ", status: " << static_cast<int>(status)
×
1332
                               << ", curl_code: " << std::to_string(curl_code);
×
1333

1334
                    std::lock_guard lock(_mutex);
×
1335
                    auto maybe_potential_camera =
1336
                        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
×
1337
                    if (maybe_potential_camera == nullptr) {
×
1338
                        LogErr() << "Failed to find camera.";
×
1339
                    }
1340

1341
                    if (status == HttpStatus::Error) {
×
1342
                        LogErr() << "File download failed with result "
×
1343
                                 << std::to_string(curl_code);
×
1344
                        maybe_potential_camera->is_fetching_camera_definition = false;
×
1345
                        maybe_potential_camera->camera_definition_result = Camera::Result::Error;
×
1346
                        notify_camera_list_with_lock();
×
1347

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

1366
            auto component_id = potential_camera.component_id;
1✔
1367

1368
            auto downloaded_filename = strip_prefix(strip_prefix(url, "mavlinkftp://"), "mftp://");
6✔
1369

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

1386
                    std::lock_guard lock(_mutex);
1✔
1387
                    auto maybe_potential_camera =
1388
                        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
1✔
1389
                    if (maybe_potential_camera == nullptr) {
1✔
1390
                        LogErr() << "Failed to find camera with ID " << component_id;
×
1391
                        return;
×
1392
                    }
1393

1394
                    if (client_result != MavlinkFtpClient::ClientResult::Success) {
1✔
1395
                        LogErr() << "File download failed with result " << client_result;
×
1396
                        maybe_potential_camera->is_fetching_camera_definition = false;
×
1397
                        maybe_potential_camera->camera_definition_result = Camera::Result::Error;
×
1398
                        notify_camera_list_with_lock();
×
1399
                        return;
×
1400
                    }
1401

1402
                    auto downloaded_filepath = _tmp_download_path / downloaded_filename;
2✔
1403

1404
                    LogDebug() << "File download finished to " << downloaded_filepath;
1✔
1405
                    if (_file_cache) {
1✔
1406
                        // Cache the file (this will move/remove the temp file as well)
1407
                        downloaded_filepath =
1✔
1408
                            _file_cache->insert(file_cache_tag, downloaded_filepath)
2✔
1409
                                .value_or(downloaded_filepath);
2✔
1410
                        LogDebug() << "Cached path: " << downloaded_filepath;
1✔
1411
                    }
1412
                    load_camera_definition_with_lock(*maybe_potential_camera, downloaded_filepath);
1✔
1413
                    maybe_potential_camera->is_fetching_camera_definition = false;
1✔
1414
                    maybe_potential_camera->camera_definition_result = Camera::Result::Success;
1✔
1415
                    notify_camera_list_with_lock();
1✔
1416
                });
1✔
1417
        } else {
1✔
1418
            LogErr() << "Unknown protocol for URL: " << url;
×
1419
            potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported;
×
1420
            notify_camera_list_with_lock();
×
1421
        }
1422
    }
1423
}
9✔
1424

1425
void CameraImpl::load_camera_definition_with_lock(
2✔
1426
    PotentialCamera& potential_camera, const std::filesystem::path& path)
1427
{
1428
    if (potential_camera.camera_definition == nullptr) {
2✔
1429
        potential_camera.camera_definition = std::make_unique<CameraDefinition>();
2✔
1430
    }
1431

1432
    if (!potential_camera.camera_definition->load_file(path.string())) {
2✔
1433
        LogErr() << "Failed to load camera definition: " << path;
×
1434
        // We can't keep something around that's not loaded correctly.
1435
        potential_camera.camera_definition = nullptr;
×
1436
        return;
×
1437
    }
1438

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

1443
    refresh_params_with_lock(potential_camera, true);
2✔
1444
}
1445

1446
void CameraImpl::process_video_information(const mavlink_message_t& message)
1✔
1447
{
1448
    mavlink_video_stream_information_t received_video_info;
1✔
1449
    mavlink_msg_video_stream_information_decode(&message, &received_video_info);
1✔
1450

1451
    std::lock_guard lock(_mutex);
1✔
1452
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
1✔
1453
        message.compid, received_video_info.camera_device_id);
1✔
1454

1455
    if (maybe_potential_camera == nullptr) {
1✔
1456
        return;
×
1457
    }
1458

1459
    auto& camera = *maybe_potential_camera;
1✔
1460

1461
    // TODO: use stream_id and count
1462
    camera.video_stream_info.status =
1✔
1463
        (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
1✔
1464
             Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1465
             Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1466
    camera.video_stream_info.spectrum =
1✔
1467
        (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
1✔
1468
             Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1469
             Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1470

1471
    auto& video_stream_info = camera.video_stream_info.settings;
1✔
1472
    video_stream_info.frame_rate_hz = received_video_info.framerate;
1✔
1473
    video_stream_info.horizontal_resolution_pix = received_video_info.resolution_h;
1✔
1474
    video_stream_info.vertical_resolution_pix = received_video_info.resolution_v;
1✔
1475
    video_stream_info.bit_rate_b_s = received_video_info.bitrate;
1✔
1476
    video_stream_info.rotation_deg = received_video_info.rotation;
1✔
1477
    video_stream_info.horizontal_fov_deg = static_cast<float>(received_video_info.hfov);
1✔
1478
    video_stream_info.uri = received_video_info.uri;
1✔
1479
    camera.video_stream_info.stream_id = received_video_info.stream_id;
1✔
1480
    camera.received_video_stream_info = true;
1✔
1481

1482
    notify_video_stream_info_with_lock(camera);
1✔
1483
}
1✔
1484

1485
void CameraImpl::process_video_stream_status(const mavlink_message_t& message)
3✔
1486
{
1487
    mavlink_video_stream_status_t received_video_stream_status;
3✔
1488
    mavlink_msg_video_stream_status_decode(&message, &received_video_stream_status);
3✔
1489

1490
    std::lock_guard lock(_mutex);
3✔
1491
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
3✔
1492
        message.compid, received_video_stream_status.camera_device_id);
3✔
1493

1494
    if (maybe_potential_camera == nullptr) {
3✔
1495
        return;
×
1496
    }
1497

1498
    auto& camera = *maybe_potential_camera;
3✔
1499

1500
    camera.video_stream_info.status =
3✔
1501
        (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
3✔
1502
             Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1503
             Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1504
    camera.video_stream_info.spectrum =
3✔
1505
        (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
3✔
1506
             Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1507
             Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1508

1509
    auto& video_stream_info = camera.video_stream_info.settings;
3✔
1510
    video_stream_info.frame_rate_hz = received_video_stream_status.framerate;
3✔
1511
    video_stream_info.horizontal_resolution_pix = received_video_stream_status.resolution_h;
3✔
1512
    video_stream_info.vertical_resolution_pix = received_video_stream_status.resolution_v;
3✔
1513
    video_stream_info.bit_rate_b_s = received_video_stream_status.bitrate;
3✔
1514
    video_stream_info.rotation_deg = received_video_stream_status.rotation;
3✔
1515
    video_stream_info.horizontal_fov_deg = static_cast<float>(received_video_stream_status.hfov);
3✔
1516

1517
    // We only set this when we get the static information rather than just the status.
1518
    // camera.received_video_stream_info = true;
1519

1520
    notify_video_stream_info_with_lock(camera);
3✔
1521
}
3✔
1522

1523
void CameraImpl::notify_video_stream_info_for_all_with_lock()
1✔
1524
{
1525
    for (auto& camera : _potential_cameras) {
2✔
1526
        notify_video_stream_info_with_lock(camera);
1✔
1527
    }
1528
}
1✔
1529

1530
void CameraImpl::notify_video_stream_info_with_lock(PotentialCamera& camera)
5✔
1531
{
1532
    if (!camera.received_video_stream_info) {
5✔
1533
        return;
4✔
1534
    }
1535

1536
    _video_stream_info_subscription_callbacks.queue(
3✔
1537
        Camera::VideoStreamUpdate{camera.component_id, camera.video_stream_info},
2✔
1538
        [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1539
}
1540

1541
void CameraImpl::notify_storage_for_all_with_lock()
1✔
1542
{
1543
    for (auto& potential_camera : potential_cameras_with_lock()) {
2✔
1544
        notify_storage_with_lock(*potential_camera);
1✔
1545
    }
1✔
1546
}
1✔
1547

1548
void CameraImpl::notify_storage_with_lock(PotentialCamera& camera)
2✔
1549
{
1550
    if (!camera.received_storage) {
2✔
1551
        return;
1✔
1552
    }
1553

1554
    _storage_subscription_callbacks.queue(
3✔
1555
        Camera::StorageUpdate{camera.component_id, camera.storage},
2✔
1556
        [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1557
}
1558

1559
void CameraImpl::receive_command_result(
2✔
1560
    MavlinkCommandSender::Result command_result, const Camera::ResultCallback& callback) const
1561
{
1562
    Camera::Result camera_result = camera_result_from_command_result(command_result);
2✔
1563

1564
    if (callback) {
2✔
1565
        _system_impl->call_user_callback([callback, camera_result]() { callback(camera_result); });
4✔
1566
    }
1567
}
2✔
1568

1569
void CameraImpl::receive_set_mode_command_result(
×
1570
    const MavlinkCommandSender::Result command_result,
1571
    const Camera::ResultCallback& callback,
1572
    const Camera::Mode mode,
1573
    int32_t component_id)
1574
{
1575
    Camera::Result camera_result = camera_result_from_command_result(command_result);
×
1576

1577
    if (callback) {
×
1578
        _system_impl->call_user_callback([callback, camera_result]() { callback(camera_result); });
×
1579
    }
1580

1581
    if (camera_result == Camera::Result::Success) {
×
1582
        std::lock_guard lock(_mutex);
×
1583
        auto maybe_potential_camera =
1584
            maybe_potential_camera_for_component_id_with_lock(component_id, 0);
×
1585
        if (maybe_potential_camera != nullptr) {
×
1586
            save_camera_mode_with_lock(*maybe_potential_camera, mode);
×
1587
        }
1588
    }
×
1589
}
×
1590

1591
void CameraImpl::notify_mode_for_all_with_lock()
×
1592
{
1593
    for (auto& camera : potential_cameras_with_lock()) {
×
1594
        notify_mode_with_lock(*camera);
×
1595
    }
×
1596
}
×
1597

1598
void CameraImpl::notify_mode_with_lock(PotentialCamera& camera)
×
1599
{
1600
    _mode_subscription_callbacks.queue(
×
1601
        Camera::ModeUpdate{camera.component_id, camera.mode},
×
1602
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1603
}
×
1604

1605
bool CameraImpl::get_possible_options_with_lock(
86✔
1606
    PotentialCamera& camera, const std::string& setting_id, std::vector<Camera::Option>& options)
1607
{
1608
    options.clear();
86✔
1609

1610
    if (!camera.camera_definition) {
86✔
1611
        LogWarn() << "Error: no camera definition available yet";
×
1612
        return false;
×
1613
    }
1614

1615
    std::vector<ParamValue> values;
86✔
1616
    if (!camera.camera_definition->get_possible_options(setting_id, values)) {
86✔
1617
        return false;
×
1618
    }
1619

1620
    for (const auto& value : values) {
312✔
1621
        Camera::Option option{};
226✔
1622
        option.option_id = value.get_string();
226✔
1623
        if (!camera.camera_definition->is_setting_range(setting_id)) {
226✔
1624
            get_option_str_with_lock(
88✔
1625
                camera, setting_id, option.option_id, option.option_description);
1626
        }
1627
        options.push_back(option);
226✔
1628
    }
226✔
1629

1630
    return !options.empty();
86✔
1631
}
86✔
1632

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

1635
{
1636
    auto prom = std::make_shared<std::promise<Camera::Result>>();
3✔
1637
    auto ret = prom->get_future();
3✔
1638

1639
    set_setting_async(
3✔
1640
        component_id, setting, [&prom](Camera::Result result) { prom->set_value(result); });
3✔
1641

1642
    return ret.get();
3✔
1643
}
3✔
1644

1645
void CameraImpl::set_setting_async(
3✔
1646
    int32_t component_id, const Camera::Setting& setting, const Camera::ResultCallback& callback)
1647
{
1648
    set_option_async(component_id, setting.setting_id, setting.option, callback);
3✔
1649
}
3✔
1650

1651
void CameraImpl::set_option_async(
3✔
1652
    int32_t component_id,
1653
    const std::string& setting_id,
1654
    const Camera::Option& option,
1655
    const Camera::ResultCallback& callback)
1656
{
1657
    std::lock_guard lock(_mutex);
3✔
1658
    auto maybe_potential_camera =
1659
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
3✔
1660
    if (maybe_potential_camera == nullptr) {
3✔
1661
        if (callback != nullptr) {
×
1662
            _system_impl->call_user_callback(
×
1663
                [callback]() { callback(Camera::Result::CameraIdInvalid); });
1664
        }
1665
        return;
×
1666
    }
1667

1668
    auto& camera = *maybe_potential_camera;
3✔
1669

1670
    if (camera.camera_definition == nullptr) {
3✔
1671
        if (callback != nullptr) {
×
1672
            _system_impl->call_user_callback(
×
1673
                [callback]() { callback(Camera::Result::Unavailable); });
1674
        }
1675
        return;
×
1676
    }
1677

1678
    // We get it first so that we have the type of the param value.
1679
    ParamValue value;
3✔
1680

1681
    if (camera.camera_definition->is_setting_range(setting_id)) {
3✔
1682
        // TODO: Get type from minimum.
1683
        std::vector<ParamValue> all_values;
×
1684
        if (!camera.camera_definition->get_all_options(setting_id, all_values)) {
×
1685
            if (callback) {
×
1686
                LogErr() << "Could not get all options to get type for range param.";
×
1687
                _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); });
×
1688
            }
1689
            return;
×
1690
        }
1691

1692
        if (all_values.empty()) {
×
1693
            if (callback) {
×
1694
                LogErr() << "Could not get any options to get type for range param.";
×
1695
                _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); });
×
1696
            }
1697
            return;
×
1698
        }
1699
        value = all_values[0];
×
1700

1701
        // Now re-use that type. This is quite ugly, but I don't know how we could do better than
1702
        // that.
1703
        if (!value.set_as_same_type(option.option_id)) {
×
1704
            if (callback) {
×
1705
                LogErr() << "Could not set option value to given type.";
×
1706
                _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); });
×
1707
            }
1708
            return;
×
1709
        }
1710

1711
    } else {
×
1712
        if (!camera.camera_definition->get_option_value(setting_id, option.option_id, value)) {
3✔
1713
            if (callback) {
×
1714
                LogErr() << "Could not get option value.";
×
1715
                _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); });
×
1716
            }
1717
            return;
×
1718
        }
1719

1720
        std::vector<ParamValue> possible_values;
3✔
1721
        camera.camera_definition->get_possible_options(setting_id, possible_values);
3✔
1722
        bool allowed = false;
3✔
1723
        for (const auto& possible_value : possible_values) {
9✔
1724
            if (value == possible_value) {
6✔
1725
                allowed = true;
3✔
1726
            }
1727
        }
1728
        if (!allowed) {
3✔
1729
            LogErr() << "Setting " << setting_id << "(" << option.option_id << ") not allowed";
×
1730
            if (callback) {
×
1731
                _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); });
×
1732
            }
1733
            return;
×
1734
        }
1735
    }
3✔
1736

1737
    _system_impl->set_param_async(
6✔
1738
        setting_id,
1739
        value,
1740
        [this, component_id, callback, setting_id, value](MavlinkParameterClient::Result result) {
15✔
1741
            std::lock_guard lock_later(_mutex);
3✔
1742
            auto maybe_potential_camera_later =
1743
                maybe_potential_camera_for_component_id_with_lock(component_id, 0);
3✔
1744
            // We already checked these fields earlier, so we don't check again.
1745
            assert(maybe_potential_camera_later != nullptr);
3✔
1746
            assert(maybe_potential_camera_later->camera_definition != nullptr);
3✔
1747

1748
            auto& camera_later = *maybe_potential_camera_later;
3✔
1749

1750
            if (result != MavlinkParameterClient::Result::Success) {
3✔
1751
                if (callback) {
×
1752
                    _system_impl->call_user_callback([callback, result]() {
×
1753
                        callback(camera_result_from_parameter_result(result));
1754
                    });
1755
                }
1756
                return;
×
1757
            }
1758

1759
            if (!camera_later.camera_definition->set_setting(setting_id, value)) {
3✔
1760
                if (callback) {
×
1761
                    _system_impl->call_user_callback(
×
1762
                        [callback]() { callback(Camera::Result::Error); });
1763
                }
1764
                return;
×
1765
            }
1766

1767
            if (callback) {
3✔
1768
                _system_impl->call_user_callback(
6✔
1769
                    [callback]() { callback(Camera::Result::Success); });
1770
            }
1771
            refresh_params_with_lock(camera_later, false);
3✔
1772
        },
3✔
1773
        this,
1774
        camera.component_id,
3✔
1775
        true);
1776
}
3✔
1777

1778
void CameraImpl::get_setting_async(
2✔
1779
    int32_t component_id,
1780
    const Camera::Setting& setting,
1781
    const Camera::GetSettingCallback& callback)
1782
{
1783
    {
1784
        std::lock_guard lock(_mutex);
2✔
1785
        auto maybe_potential_camera =
1786
            maybe_potential_camera_for_component_id_with_lock(component_id, 0);
2✔
1787
        if (maybe_potential_camera == nullptr) {
2✔
1788
            if (callback != nullptr) {
×
1789
                _system_impl->call_user_callback(
×
1790
                    [callback]() { callback(Camera::Result::CameraIdInvalid, {}); });
1791
            }
1792
            return;
×
1793
        }
1794

1795
        auto& camera = *maybe_potential_camera;
2✔
1796

1797
        if (camera.camera_definition == nullptr) {
2✔
1798
            if (callback != nullptr) {
×
1799
                _system_impl->call_user_callback(
×
1800
                    [callback]() { callback(Camera::Result::Unavailable, {}); });
1801
            }
1802
            return;
×
1803
        }
1804
    }
2✔
1805

1806
    get_option_async(
4✔
1807
        component_id,
1808
        setting.setting_id,
2✔
1809
        [this, callback](Camera::Result result, const Camera::Option& option) {
4✔
1810
            Camera::Setting new_setting{};
2✔
1811
            new_setting.option = option;
2✔
1812
            if (callback) {
2✔
1813
                _system_impl->call_user_callback(
4✔
1814
                    [callback, result, new_setting]() { callback(result, new_setting); });
1815
            }
1816
        });
2✔
1817
}
1818

1819
std::pair<Camera::Result, Camera::Setting>
1820
CameraImpl::get_setting(int32_t component_id, const Camera::Setting& setting)
2✔
1821
{
1822
    auto prom = std::make_shared<std::promise<std::pair<Camera::Result, Camera::Setting>>>();
2✔
1823
    auto ret = prom->get_future();
2✔
1824

1825
    get_setting_async(
2✔
1826
        component_id, setting, [&prom](Camera::Result result, const Camera::Setting& new_setting) {
2✔
1827
            prom->set_value(std::make_pair<>(result, new_setting));
2✔
1828
        });
2✔
1829

1830
    return ret.get();
2✔
1831
}
2✔
1832

1833
Camera::Result
1834
CameraImpl::get_option(int32_t component_id, const std::string& setting_id, Camera::Option& option)
×
1835
{
1836
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1837
    auto ret = prom->get_future();
×
1838

1839
    get_option_async(
×
1840
        component_id,
1841
        setting_id,
1842
        [prom, &option](Camera::Result result, const Camera::Option& option_gotten) {
×
1843
            prom->set_value(result);
×
1844
            if (result == Camera::Result::Success) {
×
1845
                option = option_gotten;
×
1846
            }
1847
        });
×
1848

1849
    auto status = ret.wait_for(std::chrono::seconds(1));
×
1850

1851
    if (status == std::future_status::ready) {
×
1852
        return Camera::Result::Success;
×
1853
    } else {
1854
        return Camera::Result::Timeout;
×
1855
    }
1856
}
×
1857

1858
void CameraImpl::get_option_async(
2✔
1859
    int32_t component_id,
1860
    const std::string& setting_id,
1861
    const std::function<void(Camera::Result, const Camera::Option&)>& callback)
1862
{
1863
    std::lock_guard lock(_mutex);
2✔
1864
    auto maybe_potential_camera =
1865
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
2✔
1866
    if (maybe_potential_camera == nullptr) {
2✔
1867
        if (callback != nullptr) {
×
1868
            _system_impl->call_user_callback(
×
1869
                [callback]() { callback(Camera::Result::CameraIdInvalid, {}); });
1870
        }
1871
        return;
×
1872
    }
1873

1874
    auto& camera = *maybe_potential_camera;
2✔
1875

1876
    if (camera.camera_definition == nullptr) {
2✔
1877
        if (callback != nullptr) {
×
1878
            _system_impl->call_user_callback(
×
1879
                [callback]() { callback(Camera::Result::Unavailable, {}); });
1880
        }
1881
        return;
×
1882
    }
1883

1884
    ParamValue value;
2✔
1885
    // We should have this cached and don't need to get the param.
1886
    if (camera.camera_definition->get_setting(setting_id, value)) {
2✔
1887
        if (callback) {
2✔
1888
            Camera::Option new_option{};
2✔
1889
            new_option.option_id = value.get_string();
2✔
1890
            if (!camera.camera_definition->is_setting_range(setting_id)) {
2✔
1891
                get_option_str_with_lock(
1✔
1892
                    camera, setting_id, new_option.option_id, new_option.option_description);
1893
            }
1894
            const auto temp_callback = callback;
2✔
1895
            _system_impl->call_user_callback([temp_callback, new_option]() {
4✔
1896
                temp_callback(Camera::Result::Success, new_option);
1897
            });
1898
        }
2✔
1899
    } else {
1900
        // If this still happens, we request the param, but also complain.
1901
        LogWarn() << "Setting '" << setting_id << "' not found.";
×
1902
        if (callback) {
×
1903
            const auto temp_callback = callback;
×
1904
            _system_impl->call_user_callback(
×
1905
                [temp_callback]() { temp_callback(Camera::Result::Error, {}); });
1906
        }
×
1907
    }
1908
}
2✔
1909

1910
Camera::CurrentSettingsHandle
1911
CameraImpl::subscribe_current_settings(const Camera::CurrentSettingsCallback& callback)
1✔
1912
{
1913
    std::lock_guard lock(_mutex);
1✔
1914
    auto handle = _subscribe_current_settings_callbacks.subscribe(callback);
1✔
1915

1916
    notify_current_settings_for_all_with_lock();
1✔
1917
    return handle;
2✔
1918
}
1✔
1919

1920
void CameraImpl::unsubscribe_current_settings(Camera::CurrentSettingsHandle handle)
1✔
1921
{
1922
    std::lock_guard lock(_mutex);
1✔
1923
    _subscribe_current_settings_callbacks.unsubscribe(handle);
1✔
1924
}
1✔
1925

1926
Camera::PossibleSettingOptionsHandle CameraImpl::subscribe_possible_setting_options(
1✔
1927
    const Camera::PossibleSettingOptionsCallback& callback)
1928
{
1929
    std::lock_guard lock(_mutex);
1✔
1930
    auto handle = _subscribe_possible_setting_options_callbacks.subscribe(callback);
1✔
1931

1932
    notify_possible_setting_options_for_all_with_lock();
1✔
1933
    return handle;
2✔
1934
}
1✔
1935

1936
void CameraImpl::unsubscribe_possible_setting_options(Camera::PossibleSettingOptionsHandle handle)
×
1937
{
1938
    _subscribe_possible_setting_options_callbacks.unsubscribe(handle);
×
1939
}
×
1940

1941
void CameraImpl::notify_current_settings_for_all_with_lock()
1✔
1942
{
1943
    for (auto& potential_camera : potential_cameras_with_lock()) {
2✔
1944
        if (potential_camera->camera_definition != nullptr) {
1✔
1945
            notify_current_settings_with_lock(*potential_camera);
1✔
1946
        }
1947
    }
1✔
1948
}
1✔
1949

1950
void CameraImpl::notify_possible_setting_options_for_all_with_lock()
1✔
1951
{
1952
    for (auto& potential_camera : potential_cameras_with_lock()) {
2✔
1953
        if (potential_camera->camera_definition != nullptr) {
1✔
1954
            notify_possible_setting_options_with_lock(*potential_camera);
1✔
1955
        }
1956
    }
1✔
1957
}
1✔
1958

1959
void CameraImpl::notify_current_settings_with_lock(PotentialCamera& potential_camera)
4✔
1960
{
1961
    assert(potential_camera.camera_definition != nullptr);
4✔
1962

1963
    if (_subscribe_current_settings_callbacks.empty()) {
4✔
1964
        return;
2✔
1965
    }
1966

1967
    auto possible_setting_options = get_possible_setting_options_with_lock(potential_camera);
2✔
1968
    if (possible_setting_options.first != Camera::Result::Success) {
2✔
1969
        LogErr() << "Could not get possible settings in current options subscription.";
×
1970
        return;
×
1971
    }
1972

1973
    auto& camera = potential_camera;
2✔
1974

1975
    Camera::CurrentSettingsUpdate update{};
2✔
1976
    update.component_id = potential_camera.component_id;
2✔
1977

1978
    for (auto& possible_setting : possible_setting_options.second) {
23✔
1979
        // use the cache for this, presumably we updated it right before.
1980
        ParamValue value;
21✔
1981
        if (camera.camera_definition->get_setting(possible_setting.setting_id, value)) {
21✔
1982
            Camera::Setting setting{};
11✔
1983
            setting.setting_id = possible_setting.setting_id;
11✔
1984
            setting.is_range =
11✔
1985
                camera.camera_definition->is_setting_range(possible_setting.setting_id);
11✔
1986
            get_setting_str_with_lock(camera, setting.setting_id, setting.setting_description);
11✔
1987
            setting.option.option_id = value.get_string();
11✔
1988
            if (!camera.camera_definition->is_setting_range(possible_setting.setting_id)) {
11✔
1989
                get_option_str_with_lock(
5✔
1990
                    camera,
1991
                    setting.setting_id,
1992
                    setting.option.option_id,
1993
                    setting.option.option_description);
1994
            }
1995
            update.current_settings.push_back(setting);
11✔
1996
        }
11✔
1997
    }
21✔
1998

1999
    _subscribe_current_settings_callbacks.queue(
2✔
2000
        update, [this](const auto& func) { _system_impl->call_user_callback(func); });
2✔
2001
}
2✔
2002

2003
void CameraImpl::notify_possible_setting_options_with_lock(PotentialCamera& potential_camera)
4✔
2004
{
2005
    assert(potential_camera.camera_definition != nullptr);
4✔
2006

2007
    if (_subscribe_possible_setting_options_callbacks.empty()) {
4✔
2008
        return;
2✔
2009
    }
2010

2011
    Camera::PossibleSettingOptionsUpdate update{};
2✔
2012
    update.component_id = potential_camera.component_id;
2✔
2013

2014
    auto setting_options = get_possible_setting_options_with_lock(potential_camera);
2✔
2015
    if (setting_options.second.empty()) {
2✔
2016
        return;
×
2017
    }
2018

2019
    update.setting_options = setting_options.second;
2✔
2020

2021
    _subscribe_possible_setting_options_callbacks.queue(
2✔
2022
        update, [this](const auto& func) { _system_impl->call_user_callback(func); });
2✔
2023
}
2✔
2024

2025
std::pair<Camera::Result, std::vector<Camera::SettingOptions>>
2026
CameraImpl::get_possible_setting_options(int32_t component_id)
2✔
2027
{
2028
    std::pair<Camera::Result, std::vector<Camera::SettingOptions>> result;
2✔
2029

2030
    std::lock_guard lock(_mutex);
2✔
2031
    auto maybe_potential_camera =
2032
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
2✔
2033
    if (maybe_potential_camera == nullptr) {
2✔
2034
        result.first = Camera::Result::CameraIdInvalid;
×
2035
        return result;
×
2036
    }
2037

2038
    auto& camera = *maybe_potential_camera;
2✔
2039
    if (camera.is_fetching_camera_definition || camera.camera_definition == nullptr) {
2✔
2040
        result.first = Camera::Result::Unavailable;
×
2041
        return result;
×
2042
    }
2043

2044
    return get_possible_setting_options_with_lock(*maybe_potential_camera);
2✔
2045
}
2✔
2046

2047
std::pair<Camera::Result, std::vector<Camera::SettingOptions>>
2048
CameraImpl::get_possible_setting_options_with_lock(PotentialCamera& potential_camera)
8✔
2049
{
2050
    std::pair<Camera::Result, std::vector<Camera::SettingOptions>> result;
8✔
2051

2052
    std::unordered_map<std::string, ParamValue> possible_settings;
8✔
2053
    assert(potential_camera.camera_definition != nullptr);
8✔
2054

2055
    auto& camera = potential_camera;
8✔
2056

2057
    camera.camera_definition->get_possible_settings(possible_settings);
8✔
2058

2059
    for (auto& possible_setting : possible_settings) {
94✔
2060
        Camera::SettingOptions setting_options{};
86✔
2061
        setting_options.setting_id = possible_setting.first;
86✔
2062
        setting_options.is_range =
86✔
2063
            camera.camera_definition->is_setting_range(possible_setting.first);
86✔
2064
        get_setting_str_with_lock(
86✔
2065
            camera, setting_options.setting_id, setting_options.setting_description);
2066
        get_possible_options_with_lock(camera, possible_setting.first, setting_options.options);
86✔
2067
        result.second.push_back(setting_options);
86✔
2068
    }
86✔
2069

2070
    result.first = Camera::Result::Success;
8✔
2071
    return result;
8✔
2072
}
8✔
2073

2074
void CameraImpl::refresh_params_with_lock(PotentialCamera& potential_camera, bool initial_load)
5✔
2075
{
2076
    assert(potential_camera.camera_definition != nullptr);
5✔
2077

2078
    std::vector<std::pair<std::string, ParamValue>> params;
5✔
2079
    potential_camera.camera_definition->get_unknown_params(params);
5✔
2080

2081
    if (params.empty()) {
5✔
2082
        // We're assuming that we changed one option and this did not cause
2083
        // any other possible settings to change. However, we still would
2084
        // like to notify the current settings with this one change.
2085
        notify_current_settings_with_lock(potential_camera);
3✔
2086
        notify_possible_setting_options_with_lock(potential_camera);
3✔
2087
        return;
3✔
2088
    }
2089

2090
    auto component_id = potential_camera.component_id;
2✔
2091

2092
    unsigned count = 0;
2✔
2093
    for (const auto& param : params) {
28✔
2094
        const std::string& param_name = param.first;
26✔
2095
        const ParamValue& param_value_type = param.second;
26✔
2096
        const bool is_last = (count == params.size() - 1);
26✔
2097
        if (_debugging) {
26✔
2098
            LogDebug() << "Trying to get param: " << param_name;
×
2099
        }
2100
        _system_impl->param_sender(potential_camera.component_id, true)
52✔
2101
            ->get_param_async(
26✔
2102
                param_name,
2103
                param_value_type,
2104
                [component_id, param_name, is_last, this](
26✔
2105
                    MavlinkParameterClient::Result result, const ParamValue& value) {
78✔
2106
                    if (result != MavlinkParameterClient::Result::Success) {
26✔
2107
                        return;
×
2108
                    }
2109

2110
                    std::lock_guard lock_later(_mutex);
26✔
2111
                    auto maybe_potential_camera_later =
2112
                        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
26✔
2113
                    // We already checked these fields earlier, so we don't check again.
2114
                    assert(maybe_potential_camera_later != nullptr);
26✔
2115
                    assert(maybe_potential_camera_later->camera_definition != nullptr);
26✔
2116

2117
                    auto& camera_later = *maybe_potential_camera_later;
26✔
2118

2119
                    if (camera_later.camera_definition->set_setting(param_name, value)) {
26✔
2120
                        if (_debugging) {
26✔
2121
                            LogDebug() << "Got setting for " << param_name << ": " << value;
×
2122
                        }
2123
                        return;
26✔
2124
                    }
2125

2126
                    if (is_last) {
×
2127
                        notify_current_settings_with_lock(camera_later);
×
2128
                        notify_possible_setting_options_with_lock(camera_later);
×
2129
                    }
2130
                },
26✔
2131
                this);
2132

2133
        if (initial_load) {
26✔
2134
            subscribe_to_param_changes_with_lock(potential_camera, param_name, param_value_type);
26✔
2135
        }
2136
        ++count;
26✔
2137
    }
2138
}
5✔
2139

2140
void CameraImpl::subscribe_to_param_changes_with_lock(
26✔
2141
    PotentialCamera& camera, std::string param_name, const ParamValue& param_value_type)
2142
{
2143
    auto component_id = camera.component_id;
26✔
2144
    auto changed = [this, component_id, param_name](auto new_param) {
65✔
2145
        if (_debugging) {
13✔
2146
            LogDebug() << "Got changing param: " << param_name << " -> " << new_param;
×
2147
        }
2148

2149
        std::lock_guard lock_later(_mutex);
13✔
2150

2151
        auto maybe_potential_camera_later =
2152
            maybe_potential_camera_for_component_id_with_lock(component_id, 0);
13✔
2153
        // We already checked these fields earlier, so we don't check again.
2154
        assert(maybe_potential_camera_later != nullptr);
13✔
2155
        assert(maybe_potential_camera_later->camera_definition != nullptr);
13✔
2156
        auto& camera_later = *maybe_potential_camera_later;
13✔
2157

2158
        ParamValue param_value;
13✔
2159
        param_value.set<decltype(new_param)>(new_param);
13✔
2160
        camera_later.camera_definition->set_setting(param_name, param_value);
13✔
2161
    };
39✔
2162

2163
    if (param_value_type.is<uint8_t>()) {
26✔
2164
        _system_impl->param_sender(camera.component_id, true)
×
2165
            ->subscribe_param_changed<uint8_t>(param_name, changed, this);
×
2166
    } else if (param_value_type.is<uint8_t>()) {
26✔
2167
        _system_impl->param_sender(camera.component_id, true)
×
2168
            ->subscribe_param_changed<uint16_t>(param_name, changed, this);
×
2169
    } else if (param_value_type.is<uint32_t>()) {
26✔
UNCOV
2170
        _system_impl->param_sender(camera.component_id, true)
×
UNCOV
2171
            ->subscribe_param_changed<uint32_t>(param_name, changed, this);
×
2172
    } else if (param_value_type.is<uint64_t>()) {
26✔
2173
        _system_impl->param_sender(camera.component_id, true)
×
2174
            ->subscribe_param_changed<uint64_t>(param_name, changed, this);
×
2175
    } else if (param_value_type.is<int8_t>()) {
26✔
2176
        _system_impl->param_sender(camera.component_id, true)
×
2177
            ->subscribe_param_changed<int8_t>(param_name, changed, this);
×
2178
    } else if (param_value_type.is<int16_t>()) {
26✔
2179
        _system_impl->param_sender(camera.component_id, true)
×
2180
            ->subscribe_param_changed<int16_t>(param_name, changed, this);
×
2181
    } else if (param_value_type.is<int32_t>()) {
26✔
2182
        _system_impl->param_sender(camera.component_id, true)
26✔
2183
            ->subscribe_param_changed<int32_t>(param_name, changed, this);
26✔
2184
    } else if (param_value_type.is<int64_t>()) {
×
2185
        _system_impl->param_sender(camera.component_id, true)
×
2186
            ->subscribe_param_changed<int64_t>(param_name, changed, this);
×
2187
    } else if (param_value_type.is<float>()) {
×
2188
        _system_impl->param_sender(camera.component_id, true)
×
2189
            ->subscribe_param_changed<float>(param_name, changed, this);
×
2190
    } else if (param_value_type.is<double>()) {
×
2191
        _system_impl->param_sender(camera.component_id, true)
×
2192
            ->subscribe_param_changed<double>(param_name, changed, this);
×
2193
    } else if (param_value_type.is<std::string>()) {
×
2194
        _system_impl->param_sender(camera.component_id, true)
×
2195
            ->subscribe_param_changed<std::string>(param_name, changed, this);
×
2196
    } else {
2197
        LogErr() << "Unknown type for param " << param_name;
×
2198
    }
2199
}
26✔
2200

2201
bool CameraImpl::get_setting_str_with_lock(
118✔
2202
    PotentialCamera& potential_camera, const std::string& setting_id, std::string& description)
2203
{
2204
    if (potential_camera.camera_definition == nullptr) {
118✔
2205
        return false;
×
2206
    }
2207

2208
    return potential_camera.camera_definition->get_setting_str(setting_id, description);
118✔
2209
}
2210

2211
bool CameraImpl::get_option_str_with_lock(
104✔
2212
    PotentialCamera& potential_camera,
2213
    const std::string& setting_id,
2214
    const std::string& option_id,
2215
    std::string& description)
2216
{
2217
    if (potential_camera.camera_definition == nullptr) {
104✔
2218
        return false;
×
2219
    }
2220

2221
    return potential_camera.camera_definition->get_option_str(setting_id, option_id, description);
104✔
2222
}
2223

2224
void CameraImpl::request_camera_information(uint8_t component_id)
9✔
2225
{
2226
    _system_impl->mavlink_request_message().request(
18✔
2227
        MAVLINK_MSG_ID_CAMERA_INFORMATION, fixup_component_target(component_id), nullptr);
9✔
2228
}
9✔
2229

2230
Camera::Result CameraImpl::format_storage(int32_t component_id, int32_t storage_id)
1✔
2231
{
2232
    auto prom = std::make_shared<std::promise<Camera::Result>>();
1✔
2233
    auto ret = prom->get_future();
1✔
2234

2235
    format_storage_async(
1✔
2236
        component_id, storage_id, [prom](Camera::Result result) { prom->set_value(result); });
1✔
2237

2238
    return ret.get();
1✔
2239
}
1✔
2240

2241
void CameraImpl::format_storage_async(
1✔
2242
    int32_t component_id, int32_t storage_id, const Camera::ResultCallback& callback)
2243
{
2244
    MavlinkCommandSender::CommandLong cmd_format{};
1✔
2245

2246
    cmd_format.command = MAV_CMD_STORAGE_FORMAT;
1✔
2247
    cmd_format.params.maybe_param1 = static_cast<float>(storage_id); // storage ID
1✔
2248
    cmd_format.params.maybe_param2 = 1.0f; // format
1✔
2249
    cmd_format.params.maybe_param3 = 1.0f; // clear
1✔
2250
    cmd_format.target_component_id = component_id;
1✔
2251

2252
    _system_impl->send_command_async(
1✔
2253
        cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
3✔
2254
            UNUSED(progress);
1✔
2255

2256
            receive_command_result(result, [this, callback](Camera::Result camera_result) {
1✔
2257
                callback(camera_result);
1✔
2258
            });
1✔
2259
        });
1✔
2260
}
1✔
2261

2262
Camera::Result CameraImpl::reset_settings(int32_t component_id)
1✔
2263
{
2264
    auto prom = std::make_shared<std::promise<Camera::Result>>();
1✔
2265
    auto ret = prom->get_future();
1✔
2266

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

2269
    return ret.get();
1✔
2270
}
1✔
2271

2272
void CameraImpl::reset_settings_async(int32_t component_id, const Camera::ResultCallback& callback)
1✔
2273
{
2274
    MavlinkCommandSender::CommandLong cmd_format{};
1✔
2275

2276
    cmd_format.command = MAV_CMD_RESET_CAMERA_SETTINGS;
1✔
2277
    cmd_format.params.maybe_param1 = 1.0f; // reset
1✔
2278
    cmd_format.target_component_id = component_id;
1✔
2279

2280
    _system_impl->send_command_async(
1✔
2281
        cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
3✔
2282
            UNUSED(progress);
1✔
2283

2284
            receive_command_result(result, [this, callback](Camera::Result camera_result) {
1✔
2285
                callback(camera_result);
1✔
2286
            });
1✔
2287
        });
1✔
2288
}
1✔
2289

2290
void CameraImpl::reset_following_format_storage_with_lock(PotentialCamera& camera)
×
2291
{
2292
    camera.capture_status.photo_list.clear();
×
2293
    camera.capture_status.image_count = 0;
×
2294
    camera.capture_status.image_count_at_connection = 0;
×
2295
    camera.capture_info.last_advertised_image_index = -1;
×
2296
    camera.capture_info.missing_image_retries.clear();
×
2297
}
×
2298

2299
std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>
2300
CameraImpl::list_photos(int32_t component_id, Camera::PhotosRange photos_range)
×
2301
{
2302
    std::promise<std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>> prom;
×
2303
    auto ret = prom.get_future();
×
2304

2305
    list_photos_async(
×
2306
        component_id,
2307
        photos_range,
2308
        [&prom](Camera::Result result, const std::vector<Camera::CaptureInfo>& photo_list) {
×
2309
            prom.set_value(std::make_pair(result, photo_list));
×
2310
        });
×
2311

2312
    return ret.get();
×
2313
}
×
2314

2315
void CameraImpl::list_photos_async(
×
2316
    int32_t component_id,
2317
    Camera::PhotosRange photos_range,
2318
    const Camera::ListPhotosCallback& callback)
2319
{
2320
    if (!callback) {
×
2321
        LogWarn() << "Trying to get a photo list with a null callback, ignoring...";
×
2322
        return;
×
2323
    }
2324

2325
    std::lock_guard lock(_mutex);
×
2326

2327
    auto maybe_potential_camera =
2328
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
×
2329
    if (maybe_potential_camera == nullptr) {
×
2330
        LogWarn() << "Invalid camera ID: " << component_id;
×
2331
        return;
×
2332
    }
2333
    auto& camera = *maybe_potential_camera;
×
2334

2335
    if (camera.capture_status.image_count == -1) {
×
2336
        LogErr() << "Cannot list photos: camera status has not been received yet!";
×
2337
        _system_impl->call_user_callback(
×
2338
            [callback]() { callback(Camera::Result::Error, std::vector<Camera::CaptureInfo>{}); });
2339
        return;
×
2340
    }
2341

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

2345
    if (camera.capture_status.photos_range == Camera::PhotosRange::SinceConnection &&
×
2346
        photos_range == Camera::PhotosRange::All) {
×
2347
        camera.capture_status.photos_range = photos_range;
×
2348

2349
        auto oldest_photo_it = std::min_element(
×
2350
            camera.capture_status.photo_list.begin(),
2351
            camera.capture_status.photo_list.end(),
2352
            [](auto& a, auto& b) { return a.first < b.first; });
×
2353

2354
        if (oldest_photo_it != camera.capture_status.photo_list.end()) {
×
2355
            for (int i = 0; i < oldest_photo_it->first; ++i) {
×
2356
                if (camera.capture_info.missing_image_retries.find(i) ==
×
2357
                    camera.capture_info.missing_image_retries.end()) {
×
2358
                    camera.capture_info.missing_image_retries[i] = 0;
×
2359
                }
2360
            }
2361
        }
2362
    }
2363

2364
    const int start_index = [&, this]() {
×
2365
        switch (photos_range) {
×
2366
            case Camera::PhotosRange::SinceConnection:
×
2367
                return camera.capture_status.image_count_at_connection;
×
2368
            case Camera::PhotosRange::All:
×
2369
            // FALLTHROUGH
2370
            default:
2371
                return 0;
×
2372
        }
2373
    }();
×
2374

2375
    std::vector<Camera::CaptureInfo> photo_list;
×
2376

2377
    for (const auto& capture_info : camera.capture_status.photo_list) {
×
2378
        if (capture_info.first >= start_index) {
×
2379
            photo_list.push_back(capture_info.second);
×
2380
        }
2381
    }
2382

2383
    _system_impl->call_user_callback(
×
2384
        [callback, photo_list]() { callback(Camera::Result::Success, photo_list); });
2385
}
×
2386

2387
std::pair<Camera::Result, Camera::Mode> CameraImpl::get_mode(int32_t component_id)
1✔
2388
{
2389
    std::pair<Camera::Result, Camera::Mode> result{};
1✔
2390

2391
    std::lock_guard lock(_mutex);
1✔
2392

2393
    auto maybe_potential_camera =
2394
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
1✔
2395
    if (maybe_potential_camera == nullptr) {
1✔
2396
        result.first = Camera::Result::CameraIdInvalid;
×
2397
    } else {
2398
        result.first = Camera::Result::Success;
1✔
2399
        result.second = maybe_potential_camera->mode;
1✔
2400
    }
2401

2402
    return result;
2✔
2403
}
1✔
2404

2405
std::pair<Camera::Result, Camera::Storage> CameraImpl::get_storage(int32_t component_id)
60✔
2406
{
2407
    std::pair<Camera::Result, Camera::Storage> result{};
60✔
2408

2409
    std::lock_guard lock(_mutex);
60✔
2410

2411
    auto maybe_potential_camera =
2412
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
60✔
2413
    if (maybe_potential_camera == nullptr) {
60✔
2414
        result.first = Camera::Result::CameraIdInvalid;
×
2415
    } else {
2416
        if (maybe_potential_camera->received_storage) {
60✔
2417
            result.first = Camera::Result::Success;
20✔
2418
            result.second = maybe_potential_camera->storage;
20✔
2419
        } else {
2420
            result.first = Camera::Result::Unavailable;
40✔
2421
        }
2422
    }
2423

2424
    return result;
60✔
2425
}
60✔
2426

2427
std::pair<Camera::Result, Camera::VideoStreamInfo>
2428
CameraImpl::get_video_stream_info(int32_t component_id)
×
2429
{
2430
    std::pair<Camera::Result, Camera::VideoStreamInfo> result{};
×
2431

2432
    std::lock_guard lock(_mutex);
×
2433

2434
    auto maybe_potential_camera =
2435
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
×
2436
    if (maybe_potential_camera == nullptr) {
×
2437
        result.first = Camera::Result::CameraIdInvalid;
×
2438
    } else {
2439
        result.first = Camera::Result::Success;
×
2440
        result.second = maybe_potential_camera->video_stream_info;
×
2441
    }
2442

2443
    return result;
×
2444
}
×
2445

2446
std::pair<Camera::Result, std::vector<Camera::Setting>>
2447
CameraImpl::get_current_settings(int32_t component_id)
2✔
2448
{
2449
    std::pair<Camera::Result, std::vector<Camera::Setting>> result;
2✔
2450

2451
    std::lock_guard lock(_mutex);
2✔
2452
    auto maybe_potential_camera =
2453
        maybe_potential_camera_for_component_id_with_lock(component_id, 0);
2✔
2454
    if (maybe_potential_camera == nullptr) {
2✔
2455
        result.first = Camera::Result::CameraIdInvalid;
×
2456
        return result;
×
2457
    }
2458

2459
    auto& camera = *maybe_potential_camera;
2✔
2460
    if (camera.is_fetching_camera_definition || camera.camera_definition == nullptr) {
2✔
2461
        result.first = Camera::Result::Unavailable;
×
2462
        return result;
×
2463
    }
2464

2465
    auto possible_setting_options = get_possible_setting_options_with_lock(camera);
2✔
2466
    if (possible_setting_options.first != Camera::Result::Success) {
2✔
2467
        result.first = possible_setting_options.first;
×
2468
        return result;
×
2469
    }
2470

2471
    for (auto& possible_setting : possible_setting_options.second) {
23✔
2472
        // use the cache for this, presumably we updated it right before.
2473
        ParamValue value;
21✔
2474
        if (camera.camera_definition->get_setting(possible_setting.setting_id, value)) {
21✔
2475
            Camera::Setting setting{};
21✔
2476
            setting.setting_id = possible_setting.setting_id;
21✔
2477
            setting.is_range =
21✔
2478
                camera.camera_definition->is_setting_range(possible_setting.setting_id);
21✔
2479
            get_setting_str_with_lock(camera, setting.setting_id, setting.setting_description);
21✔
2480
            setting.option.option_id = value.get_string();
21✔
2481
            if (!camera.camera_definition->is_setting_range(possible_setting.setting_id)) {
21✔
2482
                get_option_str_with_lock(
10✔
2483
                    camera,
2484
                    setting.setting_id,
2485
                    setting.option.option_id,
2486
                    setting.option.option_description);
2487
            }
2488
            result.second.push_back(setting);
21✔
2489
        }
21✔
2490
    }
21✔
2491

2492
    result.first = Camera::Result::Success;
2✔
2493
    return result;
2✔
2494
}
2✔
2495

2496
uint16_t CameraImpl::get_and_increment_capture_sequence(int32_t component_id)
2✔
2497
{
2498
    if (component_id == 0) {
2✔
2499
        // All cameras
2500
        return 0;
×
2501
    }
2502

2503
    std::lock_guard lock(_mutex);
2✔
2504

2505
    for (auto& potential_camera : _potential_cameras) {
2✔
2506
        if (potential_camera.component_id == component_id) {
2✔
2507
            return potential_camera.capture_sequence++;
2✔
2508
        }
2509
    }
2510

2511
    return 0;
×
2512
}
2✔
2513

2514
std::vector<CameraImpl::PotentialCamera*> CameraImpl::potential_cameras_with_lock()
108✔
2515
{
2516
    std::vector<CameraImpl::PotentialCamera*> result;
108✔
2517

2518
    for (auto& potential_camera : _potential_cameras) {
215✔
2519
        if (!potential_camera.maybe_information) {
107✔
2520
            continue;
×
2521
        }
2522
        result.push_back(&potential_camera);
107✔
2523
    }
2524

2525
    return result;
108✔
2526
}
2527

2528
CameraImpl::PotentialCamera* CameraImpl::maybe_potential_camera_for_component_id_with_lock(
134✔
2529
    uint8_t component_id, uint8_t camera_device_id)
2530
{
2531
    // Component Ids 1-6 means the camera is connected to the autopilot and the
2532
    // ID is set by the camera_device_id instead.
2533
    if (component_id == 1 && camera_device_id != 0) {
134✔
2534
        component_id = camera_device_id;
×
2535
    }
2536

2537
    const auto it = std::find_if(
134✔
2538
        _potential_cameras.begin(), _potential_cameras.end(), [&](auto& potential_camera) {
134✔
2539
            return potential_camera.component_id = component_id;
134✔
2540
        });
2541

2542
    if (it == _potential_cameras.end()) {
134✔
2543
        return nullptr;
×
2544
    }
2545

2546
    // How to get pointer from iterator?
2547
    return &(*it);
134✔
2548
}
2549

2550
uint8_t CameraImpl::fixup_component_target(uint8_t component_id)
35✔
2551
{
2552
    // Component Ids 1-6 means the camera is connected to the autopilot.
2553
    if (component_id >= 1 && component_id <= 6) {
35✔
2554
        return 1;
×
2555
    }
2556

2557
    return component_id;
35✔
2558
}
2559

2560
} // 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

© 2026 Coveralls, Inc