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

mavlink / MAVSDK / 14788758985

02 May 2025 04:35AM UTC coverage: 44.324% (+0.1%) from 44.223%
14788758985

Pull #2542

github

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

262 of 372 new or added lines in 17 files covered. (70.43%)

77 existing lines in 8 files now uncovered.

14760 of 33300 relevant lines covered (44.32%)

294.54 hits per line

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

55.18
/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
    _system_impl->remove_call_every(_request_missing_capture_info_cookie);
9✔
128
    _system_impl->remove_call_every(_request_slower_call_every_cookie);
9✔
129
    _system_impl->remove_call_every(_request_faster_call_every_cookie);
9✔
130

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

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

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

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

155
    return cmd;
2✔
156
}
157

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

166
    return cmd;
×
167
}
168

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

177
    return cmd;
×
178
}
179

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

188
    return cmd;
×
189
}
190

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

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

203
    return cmd;
×
204
}
205

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

216
    return cmd;
×
217
}
218

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

234
    return cmd;
×
235
}
236

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

243
    return cmd;
×
244
}
245

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

254
    return cmd;
×
255
}
256

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

265
    return cmd;
×
266
}
267

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

276
    return cmd;
×
277
}
278

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

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

291
    return cmd;
×
292
}
293

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

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

301
    return cmd_stop_photo;
1✔
302
}
303

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

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

314
    return cmd_start_video;
×
315
}
316

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

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

325
    return cmd_stop_video;
×
326
}
327

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

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

338
    return cmd_set_camera_mode;
2✔
339
}
340

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

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

350
    return cmd_start_video_streaming;
×
351
}
352

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

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

362
    return cmd_stop_video_streaming;
×
363
}
364

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

682
    return result;
105✔
683
}
684

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

691
    notify_camera_list_with_lock();
1✔
692

693
    return handle;
2✔
694
}
1✔
695

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

768
    notify_video_stream_info_for_all_with_lock();
1✔
769

770
    return handle;
2✔
771
}
1✔
772

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

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

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

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

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

850
    return camera_result;
2✔
851
}
852

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

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

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

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

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

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

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

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

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

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

933
    notify_mode_for_all_with_lock();
×
934

935
    return handle;
×
936
}
×
937

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

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

949
    notify_storage_for_all_with_lock();
1✔
950

951
    return handle;
2✔
952
}
1✔
953

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

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

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

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

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

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

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

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

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

1012
    auto& camera = *maybe_potential_camera;
4✔
1013

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

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

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

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

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

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

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

1048
    auto& camera = *maybe_potential_camera;
1✔
1049

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

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

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

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

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

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

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

1113
    auto& camera = *maybe_potential_camera;
4✔
1114

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1319
            auto component_id = potential_camera.component_id;
×
1320

1321
            auto download_path = _tmp_download_path / file_cache_tag;
×
1322

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

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

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

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

1365
            auto component_id = potential_camera.component_id;
1✔
1366

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

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

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

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

1401
                    auto downloaded_filepath = _tmp_download_path / downloaded_filename;
2✔
1402

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

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

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

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

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

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

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

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

1458
    auto& camera = *maybe_potential_camera;
1✔
1459

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

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

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

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

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

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

1497
    auto& camera = *maybe_potential_camera;
3✔
1498

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1667
    auto& camera = *maybe_potential_camera;
3✔
1668

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

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

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

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

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

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

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

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

1747
            auto& camera_later = *maybe_potential_camera_later;
3✔
1748

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

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

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

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

1794
        auto& camera = *maybe_potential_camera;
2✔
1795

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

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

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

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

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

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

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

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

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

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

1873
    auto& camera = *maybe_potential_camera;
2✔
1874

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

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

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

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

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

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

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

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

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

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

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

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

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

1972
    auto& camera = potential_camera;
2✔
1973

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

2054
    auto& camera = potential_camera;
8✔
2055

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

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

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

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

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

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

2089
    auto component_id = potential_camera.component_id;
2✔
2090

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

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

2116
                    auto& camera_later = *maybe_potential_camera_later;
26✔
2117

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

2401
    return result;
2✔
2402
}
1✔
2403

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

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

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

2423
    return result;
60✔
2424
}
60✔
2425

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

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

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

2442
    return result;
×
2443
}
×
2444

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

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

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

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

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

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

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

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

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

2510
    return 0;
×
2511
}
2✔
2512

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

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

2524
    return result;
108✔
2525
}
2526

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

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

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

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

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

2556
    return component_id;
35✔
2557
}
2558

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