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

mavlink / MAVSDK / 12824952385

17 Jan 2025 07:58AM UTC coverage: 44.646% (-0.04%) from 44.686%
12824952385

push

github

web-flow
Merge pull request #2494 from JacoboGuijar/patch-1

Update ardupilot_custom_mode.h misspelled name

14601 of 32704 relevant lines covered (44.65%)

285.68 hits per line

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

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

11
#include <algorithm>
12
#include <cassert>
13
#include <cmath>
14
#include <iterator>
15
#include <filesystem>
16
#include <functional>
17
#include <string>
18

19
namespace mavsdk {
20

21
template class CallbackList<Camera::Mode>;
22
template class CallbackList<std::vector<Camera::Setting>>;
23
template class CallbackList<std::vector<Camera::SettingOptions>>;
24
template class CallbackList<Camera::CaptureInfo>;
25
template class CallbackList<Camera::VideoStreamInfo>;
26
template class CallbackList<Camera::Storage>;
27

28
CameraImpl::CameraImpl(System& system) : PluginImplBase(system)
×
29
{
30
    _system_impl->register_plugin(this);
×
31
}
×
32

33
CameraImpl::CameraImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
9✔
34
{
35
    _system_impl->register_plugin(this);
9✔
36
}
9✔
37

38
CameraImpl::~CameraImpl()
18✔
39
{
40
    _system_impl->unregister_plugin(this);
9✔
41
}
18✔
42

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

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

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

68
    _system_impl->register_mavlink_message_handler(
9✔
69
        MAVLINK_MSG_ID_HEARTBEAT,
70
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
37✔
71
        this);
72

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

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

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

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

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

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

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

108
    _request_missing_capture_info_cookie =
9✔
109
        _system_impl->add_call_every([this]() { request_missing_capture_info(); }, 0.5);
91✔
110

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

118
void CameraImpl::deinit()
9✔
119
{
120
    _system_impl->unregister_all_mavlink_message_handlers(this);
9✔
121

122
    _system_impl->cancel_all_param(this);
9✔
123

124
    std::lock_guard lock(_mutex);
9✔
125
    _system_impl->remove_call_every(_request_missing_capture_info_cookie);
9✔
126
    _system_impl->remove_call_every(_request_slower_call_every_cookie);
9✔
127
    _system_impl->remove_call_every(_request_faster_call_every_cookie);
9✔
128

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

138
void CameraImpl::enable() {}
9✔
139
void CameraImpl::disable() {}
9✔
140

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

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

153
    return cmd;
2✔
154
}
155

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

164
    return cmd;
×
165
}
166

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

175
    return cmd;
×
176
}
177

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

186
    return cmd;
×
187
}
188

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

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

201
    return cmd;
×
202
}
203

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

214
    return cmd;
×
215
}
216

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

232
    return cmd;
×
233
}
234

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

241
    return cmd;
×
242
}
243

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

252
    return cmd;
×
253
}
254

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

263
    return cmd;
×
264
}
265

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

274
    return cmd;
×
275
}
276

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

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

289
    return cmd;
×
290
}
291

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

296
    cmd_stop_photo.command = MAV_CMD_IMAGE_STOP_CAPTURE;
1✔
297
    cmd_stop_photo.target_component_id = fixup_component_target(component_id);
1✔
298

299
    return cmd_stop_photo;
1✔
300
}
301

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

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

312
    return cmd_start_video;
×
313
}
314

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

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

323
    return cmd_stop_video;
×
324
}
325

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

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

336
    return cmd_set_camera_mode;
2✔
337
}
338

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

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

348
    return cmd_start_video_streaming;
×
349
}
350

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

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

360
    return cmd_stop_video_streaming;
×
361
}
362

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

368
    return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo));
1✔
369
}
370

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

375
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
376
}
377

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

382
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
383
}
384

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

389
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
390
}
391

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

396
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
397
}
398

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

404
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
405
}
406

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

417
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
418
}
419

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

424
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
425
}
426

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

431
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
432
}
433

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

438
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
439
}
440

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

445
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
446
}
447

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

452
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
453
}
454

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

459
    return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo_time_lapse));
1✔
460
}
461

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

466
    return camera_result_from_command_result(_system_impl->send_command(cmd_stop_photo_interval));
1✔
467
}
468

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

474
    return camera_result_from_command_result(_system_impl->send_command(cmd_start_video));
×
475
}
476

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

481
    return camera_result_from_command_result(_system_impl->send_command(cmd_stop_video));
×
482
}
483

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

662
Camera::CameraList CameraImpl::camera_list()
86✔
663
{
664
    std::lock_guard lock(_mutex);
86✔
665

666
    return camera_list_with_lock();
86✔
667
}
86✔
668

669
Camera::CameraList CameraImpl::camera_list_with_lock()
103✔
670
{
671
    Camera::CameraList result{};
103✔
672

673
    for (auto& potential_camera : potential_cameras_with_lock()) {
205✔
674
        if (!potential_camera->maybe_information) {
102✔
675
            continue;
×
676
        }
677
        result.cameras.push_back(potential_camera->maybe_information.value());
102✔
678
    }
103✔
679

680
    return result;
103✔
681
}
682

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

689
    notify_camera_list_with_lock();
1✔
690

691
    return handle;
2✔
692
}
1✔
693

694
void CameraImpl::unsubscribe_camera_list(Camera::CameraListHandle handle)
×
695
{
696
    std::lock_guard lock(_mutex);
×
697
    _camera_list_subscription_callbacks.unsubscribe(handle);
×
698
}
×
699

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

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

712
    return camera_result_from_command_result(_system_impl->send_command(command));
×
713
}
714

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

719
    return camera_result_from_command_result(_system_impl->send_command(command));
×
720
}
721

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

726
    for (auto& camera : _potential_cameras) {
12✔
727
        _system_impl->mavlink_request_message().request(
4✔
728
            MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION,
729
            fixup_component_target(camera.component_id),
2✔
730
            nullptr);
731
    }
732
}
10✔
733

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

738
    for (auto& camera : _potential_cameras) {
20✔
739
        _system_impl->mavlink_request_message().request(
12✔
740
            MAVLINK_MSG_ID_VIDEO_STREAM_STATUS,
741
            fixup_component_target(camera.component_id),
6✔
742
            nullptr);
743

744
        _system_impl->mavlink_request_message().request(
12✔
745
            MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS,
746
            fixup_component_target(camera.component_id),
6✔
747
            nullptr);
748

749
        _system_impl->mavlink_request_message().request(
12✔
750
            MAVLINK_MSG_ID_STORAGE_INFORMATION,
751
            fixup_component_target(camera.component_id),
6✔
752
            nullptr);
753

754
        _system_impl->mavlink_request_message().request(
12✔
755
            MAVLINK_MSG_ID_CAMERA_SETTINGS, fixup_component_target(camera.component_id), nullptr);
6✔
756
    }
757
}
14✔
758

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

764
    auto handle = _video_stream_info_subscription_callbacks.subscribe(callback);
1✔
765

766
    notify_video_stream_info_for_all_with_lock();
1✔
767

768
    return handle;
2✔
769
}
1✔
770

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

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

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

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

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

848
    return camera_result;
2✔
849
}
850

851
void CameraImpl::save_camera_mode_with_lock(PotentialCamera& potential_camera, Camera::Mode mode)
8✔
852
{
853
    potential_camera.mode = mode;
8✔
854

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

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

863
    if (!potential_camera.camera_definition) {
8✔
864
        return;
8✔
865
    }
866

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

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

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

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

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

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

931
    notify_mode_for_all_with_lock();
×
932

933
    return handle;
×
934
}
×
935

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

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

947
    notify_storage_for_all_with_lock();
1✔
948

949
    return handle;
2✔
950
}
1✔
951

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

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

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

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

980
    if (!found) {
37✔
981
        _potential_cameras.emplace_back(message.compid);
9✔
982
        check_potential_cameras_with_lock();
9✔
983
    }
984
}
37✔
985

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

997
void CameraImpl::process_camera_capture_status(const mavlink_message_t& message)
6✔
998
{
999
    mavlink_camera_capture_status_t camera_capture_status;
6✔
1000
    mavlink_msg_camera_capture_status_decode(&message, &camera_capture_status);
6✔
1001

1002
    std::lock_guard lock(_mutex);
6✔
1003
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
6✔
1004
        message.compid, camera_capture_status.camera_device_id);
6✔
1005

1006
    if (maybe_potential_camera == nullptr) {
6✔
1007
        return;
×
1008
    }
1009

1010
    auto& camera = *maybe_potential_camera;
6✔
1011

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

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

1025
    camera.capture_status.image_count = camera_capture_status.image_count;
6✔
1026

1027
    if (camera.capture_status.image_count_at_connection == -1) {
6✔
1028
        camera.capture_status.image_count_at_connection = camera_capture_status.image_count;
3✔
1029
    }
1030
}
6✔
1031

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

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

1042
    if (maybe_potential_camera == nullptr) {
1✔
1043
        return;
×
1044
    }
1045

1046
    auto& camera = *maybe_potential_camera;
1✔
1047

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

1056
    notify_storage_with_lock(camera);
1✔
1057
}
1✔
1058

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

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

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

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

1107
    if (maybe_potential_camera == nullptr) {
4✔
1108
        return;
×
1109
    }
1110

1111
    auto& camera = *maybe_potential_camera;
4✔
1112

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

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

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

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

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

1161
        camera.capture_info.last_advertised_image_index = capture_info.index;
4✔
1162
    }
1163

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

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

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

1204
void CameraImpl::process_camera_settings(const mavlink_message_t& message)
6✔
1205
{
1206
    mavlink_camera_settings_t camera_settings;
6✔
1207
    mavlink_msg_camera_settings_decode(&message, &camera_settings);
6✔
1208

1209
    std::lock_guard lock(_mutex);
6✔
1210
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
6✔
1211
        message.compid, camera_settings.camera_device_id);
6✔
1212

1213
    if (maybe_potential_camera == nullptr) {
6✔
1214
        return;
×
1215
    }
1216

1217
    save_camera_mode_with_lock(*maybe_potential_camera, to_camera_mode(camera_settings.mode_id));
6✔
1218
}
6✔
1219

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

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

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

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

1253
    std::lock_guard lock(_mutex);
9✔
1254

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

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

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

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

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

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

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

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

1299
    } else {
1300
        potential_camera.is_fetching_camera_definition = true;
8✔
1301

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

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

1317
            auto component_id = potential_camera.component_id;
×
1318

1319
            auto download_path = _tmp_download_path / file_cache_tag;
×
1320

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

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

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

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

1363
            auto component_id = potential_camera.component_id;
1✔
1364

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

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

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

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

1399
                    auto downloaded_filepath = _tmp_download_path / downloaded_filename;
2✔
1400

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

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

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

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

1440
    refresh_params_with_lock(potential_camera, true);
2✔
1441
}
1442

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

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

1452
    if (maybe_potential_camera == nullptr) {
1✔
1453
        return;
×
1454
    }
1455

1456
    auto& camera = *maybe_potential_camera;
1✔
1457

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

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

1479
    notify_video_stream_info_with_lock(camera);
1✔
1480
}
1✔
1481

1482
void CameraImpl::process_video_stream_status(const mavlink_message_t& message)
4✔
1483
{
1484
    mavlink_video_stream_status_t received_video_stream_status;
4✔
1485
    mavlink_msg_video_stream_status_decode(&message, &received_video_stream_status);
4✔
1486

1487
    std::lock_guard lock(_mutex);
4✔
1488
    auto maybe_potential_camera = maybe_potential_camera_for_component_id_with_lock(
4✔
1489
        message.compid, received_video_stream_status.camera_device_id);
4✔
1490

1491
    if (maybe_potential_camera == nullptr) {
4✔
1492
        return;
×
1493
    }
1494

1495
    auto& camera = *maybe_potential_camera;
4✔
1496

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

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

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

1517
    notify_video_stream_info_with_lock(camera);
4✔
1518
}
4✔
1519

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

1527
void CameraImpl::notify_video_stream_info_with_lock(PotentialCamera& camera)
6✔
1528
{
1529
    if (!camera.received_video_stream_info) {
6✔
1530
        return;
4✔
1531
    }
1532

1533
    _video_stream_info_subscription_callbacks.queue(
6✔
1534
        Camera::VideoStreamUpdate{camera.component_id, camera.video_stream_info},
4✔
1535
        [this](const auto& func) { _system_impl->call_user_callback(func); });
2✔
1536
}
1537

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1627
    return !options.empty();
98✔
1628
}
98✔
1629

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

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

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

1639
    return ret.get();
3✔
1640
}
3✔
1641

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

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

1665
    auto& camera = *maybe_potential_camera;
3✔
1666

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

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

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

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

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

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

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

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

1745
            auto& camera_later = *maybe_potential_camera_later;
3✔
1746

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

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

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

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

1792
        auto& camera = *maybe_potential_camera;
2✔
1793

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

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

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

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

1827
    return ret.get();
2✔
1828
}
2✔
1829

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

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

1846
    auto status = ret.wait_for(std::chrono::seconds(1));
×
1847

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

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

1871
    auto& camera = *maybe_potential_camera;
2✔
1872

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

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

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

1913
    notify_current_settings_for_all_with_lock();
1✔
1914
    return handle;
2✔
1915
}
1✔
1916

1917
void CameraImpl::unsubscribe_current_settings(Camera::CurrentSettingsHandle handle)
×
1918
{
1919
    std::lock_guard lock(_mutex);
×
1920
    _subscribe_current_settings_callbacks.unsubscribe(handle);
×
1921
}
×
1922

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

1929
    notify_possible_setting_options_for_all_with_lock();
1✔
1930
    return handle;
2✔
1931
}
1✔
1932

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

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

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

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

1960
    if (_subscribe_current_settings_callbacks.empty()) {
4✔
1961
        return;
1✔
1962
    }
1963

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

1970
    auto& camera = potential_camera;
3✔
1971

1972
    Camera::CurrentSettingsUpdate update{};
3✔
1973
    update.component_id = potential_camera.component_id;
3✔
1974

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

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

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

2004
    if (_subscribe_possible_setting_options_callbacks.empty()) {
4✔
2005
        return;
2✔
2006
    }
2007

2008
    Camera::PossibleSettingOptionsUpdate update{};
2✔
2009
    update.component_id = potential_camera.component_id;
2✔
2010

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

2016
    update.setting_options = setting_options.second;
2✔
2017

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

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

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

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

2041
    return get_possible_setting_options_with_lock(*maybe_potential_camera);
2✔
2042
}
2✔
2043

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

2049
    std::unordered_map<std::string, ParamValue> possible_settings;
9✔
2050
    assert(potential_camera.camera_definition != nullptr);
9✔
2051

2052
    auto& camera = potential_camera;
9✔
2053

2054
    camera.camera_definition->get_possible_settings(possible_settings);
9✔
2055

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

2067
    result.first = Camera::Result::Success;
9✔
2068
    return result;
9✔
2069
}
9✔
2070

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

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

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

2087
    auto component_id = potential_camera.component_id;
2✔
2088

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

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

2114
                    auto& camera_later = *maybe_potential_camera_later;
26✔
2115

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

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

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

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

2146
        std::lock_guard lock_later(_mutex);
12✔
2147

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

2155
        ParamValue param_value;
12✔
2156
        param_value.set<decltype(new_param)>(new_param);
12✔
2157
        camera_later.camera_definition->set_setting(param_name, param_value);
12✔
2158
    };
38✔
2159

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

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

2205
    return potential_camera.camera_definition->get_setting_str(setting_id, description);
152✔
2206
}
2207

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

2218
    return potential_camera.camera_definition->get_option_str(setting_id, option_id, description);
125✔
2219
}
2220

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

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

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

2235
    return ret.get();
1✔
2236
}
1✔
2237

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

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

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

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

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

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

2266
    return ret.get();
1✔
2267
}
1✔
2268

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

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

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

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

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

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

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

2309
    return ret.get();
×
2310
}
×
2311

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

2322
    std::lock_guard lock(_mutex);
×
2323

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

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

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

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

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

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

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

2372
    std::vector<Camera::CaptureInfo> photo_list;
×
2373

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

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

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

2388
    std::lock_guard lock(_mutex);
1✔
2389

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

2399
    return result;
2✔
2400
}
1✔
2401

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

2406
    std::lock_guard lock(_mutex);
60✔
2407

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

2421
    return result;
60✔
2422
}
60✔
2423

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

2429
    std::lock_guard lock(_mutex);
×
2430

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

2440
    return result;
×
2441
}
×
2442

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

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

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

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

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

2489
    result.first = Camera::Result::Success;
2✔
2490
    return result;
2✔
2491
}
2✔
2492

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

2500
    std::lock_guard lock(_mutex);
2✔
2501

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

2508
    return 0;
×
2509
}
2✔
2510

2511
std::vector<CameraImpl::PotentialCamera*> CameraImpl::potential_cameras_with_lock()
106✔
2512
{
2513
    std::vector<CameraImpl::PotentialCamera*> result;
106✔
2514

2515
    for (auto& potential_camera : _potential_cameras) {
211✔
2516
        if (!potential_camera.maybe_information) {
105✔
2517
            continue;
×
2518
        }
2519
        result.push_back(&potential_camera);
105✔
2520
    }
2521

2522
    return result;
106✔
2523
}
2524

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

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

2539
    if (it == _potential_cameras.end()) {
138✔
2540
        return nullptr;
×
2541
    }
2542

2543
    // How to get pointer from iterator?
2544
    return &(*it);
138✔
2545
}
2546

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

2554
    return component_id;
40✔
2555
}
2556

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

© 2025 Coveralls, Inc