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

mavlink / MAVSDK / 7233481265

16 Dec 2023 06:06PM UTC coverage: 37.088% (+0.09%) from 36.997%
7233481265

push

github

web-flow
Merge pull request #2192 from mavlink/pr-fix-sysid-filter

core: fix incoming messages by sysid

32 of 52 new or added lines in 4 files covered. (61.54%)

1 existing line in 1 file now uncovered.

10002 of 26968 relevant lines covered (37.09%)

113.62 hits per line

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

4.73
/src/mavsdk/plugins/camera/camera_impl.cpp
1
#include "camera_impl.h"
2
#include "camera_definition.h"
3
#include "system.h"
4
#include "mavsdk_math.h"
5
#include "http_loader.h"
6
#include "camera_definition_files.h"
7
#include "unused.h"
8
#include "callback_list.tpp"
9

10
#include <functional>
11
#include <cmath>
12
#include <sstream>
13

14
namespace mavsdk {
15

16
template class CallbackList<Camera::Mode>;
17
template class CallbackList<std::vector<Camera::Setting>>;
18
template class CallbackList<std::vector<Camera::SettingOptions>>;
19
template class CallbackList<Camera::CaptureInfo>;
20
template class CallbackList<Camera::VideoStreamInfo>;
21
template class CallbackList<Camera::Status>;
22

23
CameraImpl::CameraImpl(System& system) : PluginImplBase(system)
×
24
{
25
    _system_impl->register_plugin(this);
×
26
}
×
27

28
CameraImpl::CameraImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
1✔
29
{
30
    _system_impl->register_plugin(this);
1✔
31
}
1✔
32

33
CameraImpl::~CameraImpl()
1✔
34
{
35
    _system_impl->unregister_plugin(this);
1✔
36
}
1✔
37

38
void CameraImpl::init()
1✔
39
{
40
    _system_impl->register_mavlink_message_handler_with_compid(
2✔
41
        MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS,
42
        _camera_id + MAV_COMP_ID_CAMERA,
1✔
43
        [this](const mavlink_message_t& message) { process_camera_capture_status(message); },
×
44
        this);
45

46
    _system_impl->register_mavlink_message_handler_with_compid(
2✔
47
        MAVLINK_MSG_ID_STORAGE_INFORMATION,
48
        _camera_id + MAV_COMP_ID_CAMERA,
1✔
49
        [this](const mavlink_message_t& message) { process_storage_information(message); },
×
50
        this);
51

52
    _system_impl->register_mavlink_message_handler_with_compid(
2✔
53
        MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED,
54
        _camera_id + MAV_COMP_ID_CAMERA,
1✔
55
        [this](const mavlink_message_t& message) { process_camera_image_captured(message); },
×
56
        this);
57

58
    _system_impl->register_mavlink_message_handler_with_compid(
2✔
59
        MAVLINK_MSG_ID_CAMERA_SETTINGS,
60
        _camera_id + MAV_COMP_ID_CAMERA,
1✔
61
        [this](const mavlink_message_t& message) { process_camera_settings(message); },
×
62
        this);
63

64
    _system_impl->register_mavlink_message_handler_with_compid(
2✔
65
        MAVLINK_MSG_ID_CAMERA_INFORMATION,
66
        _camera_id + MAV_COMP_ID_CAMERA,
1✔
67
        [this](const mavlink_message_t& message) { process_camera_information(message); },
×
68
        this);
69

70
    _system_impl->register_mavlink_message_handler_with_compid(
2✔
71
        MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION,
72
        _camera_id + MAV_COMP_ID_CAMERA,
1✔
73
        [this](const mavlink_message_t& message) { process_video_information(message); },
×
74
        this);
75

76
    _system_impl->register_mavlink_message_handler_with_compid(
2✔
77
        MAVLINK_MSG_ID_VIDEO_STREAM_STATUS,
78
        _camera_id + MAV_COMP_ID_CAMERA,
1✔
79
        [this](const mavlink_message_t& message) { process_video_stream_status(message); },
×
80
        this);
81

82
    if (_system_impl->has_autopilot()) {
1✔
83
        _system_impl->register_mavlink_message_handler(
×
84
            MAVLINK_MSG_ID_FLIGHT_INFORMATION,
85
            [this](const mavlink_message_t& message) { process_flight_information(message); },
×
86
            this);
87
    }
88

89
    _system_impl->add_call_every(
1✔
90
        [this]() { check_connection_status(); }, 0.5, &_check_connection_status_call_every_cookie);
×
91

92
    _system_impl->add_call_every(
1✔
93
        [this]() { request_missing_capture_info(); }, 0.5, &_request_missing_capture_info_cookie);
×
94
}
1✔
95

96
void CameraImpl::deinit()
1✔
97
{
98
    _system_impl->remove_call_every(_request_missing_capture_info_cookie);
1✔
99
    _system_impl->remove_call_every(_check_connection_status_call_every_cookie);
1✔
100
    _system_impl->remove_call_every(_status.call_every_cookie);
1✔
101
    _system_impl->remove_call_every(_camera_information_call_every_cookie);
1✔
102
    _system_impl->remove_call_every(_flight_information_call_every_cookie);
1✔
103
    _system_impl->remove_call_every(_mode.call_every_cookie);
1✔
104
    _system_impl->remove_call_every(_video_stream_info.call_every_cookie);
1✔
105
    _system_impl->unregister_all_mavlink_message_handlers(this);
1✔
106
    _system_impl->cancel_all_param(this);
1✔
107

108
    {
109
        std::lock_guard<std::mutex> lock(_status.mutex);
2✔
110
        _status.subscription_callbacks.clear();
1✔
111
    }
112

113
    {
114
        std::lock_guard<std::mutex> lock(_mode.mutex);
2✔
115
        _mode.subscription_callbacks.clear();
1✔
116
    }
117

118
    {
119
        std::lock_guard<std::mutex> lock(_capture_info.mutex);
2✔
120
        _capture_info.callbacks.clear();
1✔
121
    }
122

123
    {
124
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
2✔
125
        _video_stream_info.subscription_callbacks.clear();
1✔
126
    }
127

128
    {
129
        std::lock_guard<std::mutex> lock(_information.mutex);
2✔
130
        _information.subscription_callbacks.clear();
1✔
131
    }
132

133
    {
134
        std::lock_guard<std::mutex> lock(_subscribe_current_settings.mutex);
2✔
135
        _subscribe_current_settings.callbacks.clear();
1✔
136
    }
137

138
    {
139
        std::lock_guard<std::mutex> lock(_subscribe_possible_setting_options.mutex);
2✔
140
        _subscribe_possible_setting_options.callbacks.clear();
1✔
141
    }
142

143
    _camera_found = false;
1✔
144
}
1✔
145

146
Camera::Result CameraImpl::prepare()
×
147
{
148
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
149
    auto ret = prom->get_future();
×
150

151
    prepare_async([&prom](Camera::Result result) { prom->set_value(result); });
×
152

153
    return ret.get();
×
154
}
155

156
void CameraImpl::prepare_async(const Camera::ResultCallback& callback)
×
157
{
158
    auto temp_callback = callback;
×
159

160
    std::lock_guard<std::mutex> lock(_information.mutex);
×
161

162
    if (_camera_definition) {
×
163
        _system_impl->call_user_callback(
×
164
            [temp_callback]() { temp_callback(Camera::Result::Success); });
165
    } else {
166
        _camera_definition_callback = [this, temp_callback](bool has_succeeded) {
×
167
            if (has_succeeded) {
×
168
                temp_callback(Camera::Result::Success);
×
169
            } else {
170
                temp_callback(Camera::Result::Error);
×
171
            }
172
            _camera_definition_callback = nullptr;
×
173
        };
×
174

175
        if (_has_camera_definition_timed_out) {
×
176
            // Try to download the camera_definition again
177
            _has_camera_definition_timed_out = false;
×
178
            request_camera_information();
×
179
        }
180
    }
181
}
×
182

183
void CameraImpl::check_connection_status()
×
184
{
185
    // FIXME: This is a workaround because we don't want to be tied to the
186
    // discovery of an autopilot which triggers enable() and disable() but
187
    // we are interested if a camera is connected or not.
188
    if (_system_impl->has_camera(_camera_id)) {
×
189
        if (!_camera_found) {
×
190
            _camera_found = true;
×
191
            manual_enable();
×
192
        }
193
    }
194
}
×
195

196
void CameraImpl::enable()
1✔
197
{
198
    // FIXME: We check for the connection status manually because
199
    // we're not interested in the connection state of the autopilot
200
    // but only the camera.
201
}
1✔
202

203
void CameraImpl::manual_enable()
×
204
{
205
    refresh_params();
×
206

207
    request_status();
×
208
    request_camera_information();
×
209

210
    _system_impl->add_call_every(
×
211
        [this]() { request_camera_information(); }, 10.0, &_camera_information_call_every_cookie);
×
212

213
    _system_impl->add_call_every([this]() { request_status(); }, 5.0, &_status.call_every_cookie);
×
214

215
    // for backwards compatibility with Yuneec drones
216
    if (_system_impl->has_autopilot()) {
×
217
        request_flight_information();
×
218

219
        _system_impl->add_call_every(
×
220
            [this]() { request_flight_information(); },
×
221
            10.0,
222
            &_flight_information_call_every_cookie);
223
    }
224
}
×
225

226
void CameraImpl::disable()
1✔
227
{
228
    // FIXME: We check for the connection status manually because
229
    // we're not interested in the connection state of the autopilot
230
    // but only the camera.
231
}
1✔
232

233
void CameraImpl::manual_disable()
×
234
{
235
    invalidate_params();
×
236
    _system_impl->remove_call_every(_camera_information_call_every_cookie);
×
237
    _system_impl->remove_call_every(_status.call_every_cookie);
×
238

239
    if (_flight_information_call_every_cookie) {
×
240
        _system_impl->remove_call_every(_flight_information_call_every_cookie);
×
241
    }
242

243
    _camera_found = false;
×
244
}
×
245

246
void CameraImpl::update_component()
×
247
{
248
    uint8_t cmp_id = _camera_id + MAV_COMP_ID_CAMERA;
×
NEW
249
    _system_impl->update_component_id_messages_handler(
×
250
        MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, cmp_id, this);
251

NEW
252
    _system_impl->update_component_id_messages_handler(
×
253
        MAVLINK_MSG_ID_STORAGE_INFORMATION, cmp_id, this);
254

NEW
255
    _system_impl->update_component_id_messages_handler(
×
256
        MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, cmp_id, this);
257

NEW
258
    _system_impl->update_component_id_messages_handler(
×
259
        MAVLINK_MSG_ID_CAMERA_SETTINGS, cmp_id, this);
260

NEW
261
    _system_impl->update_component_id_messages_handler(
×
262
        MAVLINK_MSG_ID_CAMERA_INFORMATION, cmp_id, this);
263

NEW
264
    _system_impl->update_component_id_messages_handler(
×
265
        MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, cmp_id, this);
266

NEW
267
    _system_impl->update_component_id_messages_handler(
×
268
        MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, cmp_id, this);
269
}
×
270

271
Camera::Result CameraImpl::select_camera(const size_t id)
×
272
{
273
    static constexpr std::size_t MAX_SUPPORTED_ID = 5;
274

275
    if (id > MAX_SUPPORTED_ID) {
×
276
        return Camera::Result::WrongArgument;
×
277
    }
278

279
    // camera component IDs go from 100 to 105.
280
    _camera_id = id;
×
281

282
    // We should probably reload everything to make sure the
283
    // correct  camera is initialized.
284
    update_component();
×
285
    manual_disable();
×
286
    manual_enable();
×
287

288
    return Camera::Result::Success;
×
289
}
290

291
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_flight_information()
×
292
{
293
    MavlinkCommandSender::CommandLong command_flight_information{};
×
294

295
    command_flight_information.command = MAV_CMD_REQUEST_FLIGHT_INFORMATION;
×
296
    command_flight_information.params.maybe_param1 = 1.0f; // Request it
×
297
    command_flight_information.target_component_id = MAV_COMP_ID_AUTOPILOT1;
×
298

299
    return command_flight_information;
×
300
}
301

302
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_camera_info()
×
303
{
304
    MavlinkCommandSender::CommandLong command_camera_info{};
×
305

306
    command_camera_info.command = MAV_CMD_REQUEST_CAMERA_INFORMATION;
×
307
    command_camera_info.params.maybe_param1 = 1.0f; // Request it
×
308
    command_camera_info.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
309

310
    return command_camera_info;
×
311
}
312

313
MavlinkCommandSender::CommandLong
314
CameraImpl::make_command_take_photo(float interval_s, float no_of_photos)
×
315
{
316
    MavlinkCommandSender::CommandLong cmd_take_photo{};
×
317

318
    cmd_take_photo.command = MAV_CMD_IMAGE_START_CAPTURE;
×
319
    cmd_take_photo.params.maybe_param1 = 0.0f; // Reserved, set to 0
×
320
    cmd_take_photo.params.maybe_param2 = interval_s;
×
321
    cmd_take_photo.params.maybe_param3 = no_of_photos;
×
322
    cmd_take_photo.params.maybe_param4 = static_cast<float>(_capture.sequence++);
×
323
    cmd_take_photo.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
324

325
    return cmd_take_photo;
×
326
}
327

328
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_photo()
×
329
{
330
    MavlinkCommandSender::CommandLong cmd_stop_photo{};
×
331

332
    cmd_stop_photo.command = MAV_CMD_IMAGE_STOP_CAPTURE;
×
333
    cmd_stop_photo.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
334

335
    return cmd_stop_photo;
×
336
}
337

338
MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video(float capture_status_rate_hz)
×
339
{
340
    MavlinkCommandSender::CommandLong cmd_start_video{};
×
341

342
    cmd_start_video.command = MAV_CMD_VIDEO_START_CAPTURE;
×
343
    cmd_start_video.params.maybe_param1 = 0.f; // Reserved, set to 0
×
344
    cmd_start_video.params.maybe_param2 = capture_status_rate_hz;
×
345
    cmd_start_video.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
346

347
    return cmd_start_video;
×
348
}
349

350
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video()
×
351
{
352
    MavlinkCommandSender::CommandLong cmd_stop_video{};
×
353

354
    cmd_stop_video.command = MAV_CMD_VIDEO_STOP_CAPTURE;
×
355
    cmd_stop_video.params.maybe_param1 = 0.f; // Reserved, set to 0
×
356
    cmd_stop_video.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
357

358
    return cmd_stop_video;
×
359
}
360

361
MavlinkCommandSender::CommandLong CameraImpl::make_command_set_camera_mode(float mavlink_mode)
×
362
{
363
    MavlinkCommandSender::CommandLong cmd_set_camera_mode{};
×
364

365
    cmd_set_camera_mode.command = MAV_CMD_SET_CAMERA_MODE;
×
366
    cmd_set_camera_mode.params.maybe_param1 = 0.0f; // Reserved, set to 0
×
367
    cmd_set_camera_mode.params.maybe_param2 = mavlink_mode;
×
368
    cmd_set_camera_mode.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
369

370
    return cmd_set_camera_mode;
×
371
}
372

373
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_camera_settings()
×
374
{
375
    MavlinkCommandSender::CommandLong cmd_req_camera_settings{};
×
376

377
    cmd_req_camera_settings.command = MAV_CMD_REQUEST_CAMERA_SETTINGS;
×
378
    cmd_req_camera_settings.params.maybe_param1 = 1.f; // Request it
×
379
    cmd_req_camera_settings.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
380

381
    return cmd_req_camera_settings;
×
382
}
383

384
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_camera_capture_status()
×
385
{
386
    MavlinkCommandSender::CommandLong cmd_req_camera_cap_stat{};
×
387

388
    cmd_req_camera_cap_stat.command = MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS;
×
389
    cmd_req_camera_cap_stat.params.maybe_param1 = 1.0f; // Request it
×
390
    cmd_req_camera_cap_stat.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
391

392
    return cmd_req_camera_cap_stat;
×
393
}
394

395
MavlinkCommandSender::CommandLong
396
CameraImpl::make_command_request_camera_image_captured(const size_t photo_id)
×
397
{
398
    MavlinkCommandSender::CommandLong cmd_req_camera_image_captured{};
×
399

400
    cmd_req_camera_image_captured.command = MAV_CMD_REQUEST_MESSAGE;
×
401
    cmd_req_camera_image_captured.params.maybe_param1 =
×
402
        static_cast<float>(MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED);
×
403
    cmd_req_camera_image_captured.params.maybe_param2 = static_cast<float>(photo_id);
×
404
    cmd_req_camera_image_captured.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
405

406
    return cmd_req_camera_image_captured;
×
407
}
408

409
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_storage_info()
×
410
{
411
    MavlinkCommandSender::CommandLong cmd_req_storage_info{};
×
412

413
    cmd_req_storage_info.command = MAV_CMD_REQUEST_STORAGE_INFORMATION;
×
414
    cmd_req_storage_info.params.maybe_param1 = 0.f; // Reserved, set to 0
×
415
    cmd_req_storage_info.params.maybe_param2 = 1.f; // Request it
×
416
    cmd_req_storage_info.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
417

418
    return cmd_req_storage_info;
×
419
}
420

421
MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video_streaming()
×
422
{
423
    MavlinkCommandSender::CommandLong cmd_start_video_streaming{};
×
424

425
    cmd_start_video_streaming.command = MAV_CMD_VIDEO_START_STREAMING;
×
426
    cmd_start_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
427

428
    return cmd_start_video_streaming;
×
429
}
430

431
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video_streaming()
×
432
{
433
    MavlinkCommandSender::CommandLong cmd_stop_video_streaming{};
×
434

435
    cmd_stop_video_streaming.command = MAV_CMD_VIDEO_STOP_STREAMING;
×
436
    cmd_stop_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
437

438
    return cmd_stop_video_streaming;
×
439
}
440

441
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_video_stream_info()
×
442
{
443
    MavlinkCommandSender::CommandLong cmd_req_video_stream_info{};
×
444

445
    cmd_req_video_stream_info.command = MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION;
×
446
    cmd_req_video_stream_info.params.maybe_param2 = 1.0f;
×
447
    cmd_req_video_stream_info.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
448

449
    return cmd_req_video_stream_info;
×
450
}
451

452
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_video_stream_status()
×
453
{
454
    MavlinkCommandSender::CommandLong cmd_req_video_stream_status{};
×
455

456
    cmd_req_video_stream_status.command = MAV_CMD_REQUEST_VIDEO_STREAM_STATUS;
×
457
    cmd_req_video_stream_status.params.maybe_param2 = 1.0f;
×
458
    cmd_req_video_stream_status.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
459

460
    return cmd_req_video_stream_status;
×
461
}
462

463
Camera::Result CameraImpl::take_photo()
×
464
{
465
    // TODO: check whether we are in photo mode.
466

467
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
468

469
    // Take 1 photo only with no interval
470
    auto cmd_take_photo = make_command_take_photo(0.f, 1.0f);
×
471

472
    return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo));
×
473
}
474

475
Camera::Result CameraImpl::start_photo_interval(float interval_s)
×
476
{
477
    if (!interval_valid(interval_s)) {
×
478
        return Camera::Result::WrongArgument;
×
479
    }
480

481
    // TODO: check whether we are in photo mode.
482

483
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
484

485
    auto cmd_take_photo_time_lapse = make_command_take_photo(interval_s, 0.f);
×
486

487
    return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo_time_lapse));
×
488
}
489

490
Camera::Result CameraImpl::stop_photo_interval()
×
491
{
492
    auto cmd_stop_photo_interval = make_command_stop_photo();
×
493

494
    return camera_result_from_command_result(_system_impl->send_command(cmd_stop_photo_interval));
×
495
}
496

497
Camera::Result CameraImpl::start_video()
×
498
{
499
    // TODO: check whether video capture is already in progress.
500
    // TODO: check whether we are in video mode.
501

502
    // Capture status rate is not set
503
    auto cmd_start_video = make_command_start_video(0.f);
×
504

505
    return camera_result_from_command_result(_system_impl->send_command(cmd_start_video));
×
506
}
507

508
Camera::Result CameraImpl::stop_video()
×
509
{
510
    auto cmd_stop_video = make_command_stop_video();
×
511

512
    {
513
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
514
        _video_stream_info.data.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning;
×
515
    }
516

517
    return camera_result_from_command_result(_system_impl->send_command(cmd_stop_video));
×
518
}
519

520
void CameraImpl::take_photo_async(const Camera::ResultCallback& callback)
×
521
{
522
    // TODO: check whether we are in photo mode.
523

524
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
525

526
    // Take 1 photo only with no interval
527
    auto cmd_take_photo = make_command_take_photo(0.f, 1.0f);
×
528

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

535
void CameraImpl::start_photo_interval_async(
×
536
    float interval_s, const Camera::ResultCallback& callback)
537
{
538
    if (!interval_valid(interval_s)) {
×
539
        const auto temp_callback = callback;
×
540
        _system_impl->call_user_callback(
×
541
            [temp_callback]() { temp_callback(Camera::Result::WrongArgument); });
542
        return;
×
543
    }
544

545
    // TODO: check whether we are in photo mode.
546

547
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
548

549
    auto cmd_take_photo_time_lapse = make_command_take_photo(interval_s, 0.f);
×
550

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

557
void CameraImpl::stop_photo_interval_async(const Camera::ResultCallback& callback)
×
558
{
559
    auto cmd_stop_photo_interval = make_command_stop_photo();
×
560

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

567
void CameraImpl::start_video_async(const Camera::ResultCallback& callback)
×
568
{
569
    // TODO: check whether video capture is already in progress.
570
    // TODO: check whether we are in video mode.
571

572
    // Capture status rate is not set
573
    auto cmd_start_video = make_command_start_video(0.f);
×
574

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

581
void CameraImpl::stop_video_async(const Camera::ResultCallback& callback)
×
582
{
583
    auto cmd_stop_video = make_command_stop_video();
×
584

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

591
Camera::Information CameraImpl::information() const
×
592
{
593
    std::lock_guard<std::mutex> lock(_information.mutex);
×
594

595
    return _information.data;
×
596
}
597

598
Camera::InformationHandle
599
CameraImpl::subscribe_information(const Camera::InformationCallback& callback)
×
600
{
601
    std::lock_guard<std::mutex> lock(_information.mutex);
×
602
    auto handle = _information.subscription_callbacks.subscribe(callback);
×
603

604
    return handle;
×
605
}
606

607
void CameraImpl::unsubscribe_information(Camera::InformationHandle handle)
×
608
{
609
    std::lock_guard<std::mutex> lock(_information.mutex);
×
610
    _information.subscription_callbacks.unsubscribe(handle);
×
611
}
×
612

613
Camera::Result CameraImpl::start_video_streaming()
×
614
{
615
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
616

617
    if (_video_stream_info.available &&
×
618
        _video_stream_info.data.status == Camera::VideoStreamInfo::VideoStreamStatus::InProgress) {
×
619
        return Camera::Result::InProgress;
×
620
    }
621

622
    // TODO Check whether we're in video mode
623
    auto command = make_command_start_video_streaming();
×
624

625
    auto result = camera_result_from_command_result(_system_impl->send_command(command));
×
626
    // if (result == Camera::Result::Success) {
627
    // Cache video stream info; app may query immediately next.
628
    // TODO: check if we can/should do that.
629
    // auto info = get_video_stream_info();
630
    //}
631
    return result;
×
632
}
633

634
Camera::Result CameraImpl::stop_video_streaming()
×
635
{
636
    // TODO I think we need to maintain current state, whether we issued
637
    // video capture request or video streaming request, etc.We shouldn't
638
    // send stop video streaming if we've not started it!
639
    auto command = make_command_stop_video_streaming();
×
640

641
    auto result = camera_result_from_command_result(_system_impl->send_command(command));
×
642
    {
643
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
644
        // TODO: check if we can/should do that.
645
        _video_stream_info.data.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning;
×
646
    }
647
    return result;
×
648
}
649

650
void CameraImpl::request_video_stream_info()
×
651
{
652
    _system_impl->send_command_async(make_command_request_video_stream_info(), nullptr);
×
653
    _system_impl->send_command_async(make_command_request_video_stream_status(), nullptr);
×
654
}
×
655

656
Camera::VideoStreamInfo CameraImpl::video_stream_info()
×
657
{
658
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
659

660
    return _video_stream_info.data;
×
661
}
662

663
Camera::VideoStreamInfoHandle
664
CameraImpl::subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& callback)
×
665
{
666
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
667

668
    auto handle = _video_stream_info.subscription_callbacks.subscribe(callback);
×
669

670
    if (callback) {
×
671
        _system_impl->add_call_every(
×
672
            [this]() { request_video_stream_info(); }, 1.0, &_video_stream_info.call_every_cookie);
×
673
    } else {
674
        _system_impl->remove_call_every(_video_stream_info.call_every_cookie);
×
675
    }
676

677
    return handle;
×
678
}
679

680
void CameraImpl::unsubscribe_video_stream_info(Camera::VideoStreamInfoHandle handle)
×
681
{
682
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
683
    _video_stream_info.subscription_callbacks.unsubscribe(handle);
×
684
}
×
685

686
Camera::Result
687
CameraImpl::camera_result_from_command_result(const MavlinkCommandSender::Result command_result)
×
688
{
689
    switch (command_result) {
×
690
        case MavlinkCommandSender::Result::Success:
×
691
            return Camera::Result::Success;
×
692
        case MavlinkCommandSender::Result::NoSystem:
×
693
            // FALLTHROUGH
694
        case MavlinkCommandSender::Result::ConnectionError:
695
            // FALLTHROUGH
696
        case MavlinkCommandSender::Result::Busy:
697
            return Camera::Result::Error;
×
698
        case MavlinkCommandSender::Result::Denied:
×
699
            // FALLTHROUGH
700
        case MavlinkCommandSender::Result::TemporarilyRejected:
701
            return Camera::Result::Denied;
×
702
        case MavlinkCommandSender::Result::Timeout:
×
703
            return Camera::Result::Timeout;
×
704
        default:
×
705
            return Camera::Result::Unknown;
×
706
    }
707
}
708

709
Camera::Result CameraImpl::camera_result_from_parameter_result(
×
710
    const MavlinkParameterClient::Result parameter_result)
711
{
712
    switch (parameter_result) {
×
713
        case MavlinkParameterClient::Result::Success:
×
714
            return Camera::Result::Success;
×
715
        case MavlinkParameterClient::Result::Timeout:
×
716
            return Camera::Result::Timeout;
×
717
        case MavlinkParameterClient::Result::ConnectionError:
×
718
            return Camera::Result::Error;
×
719
        case MavlinkParameterClient::Result::WrongType:
×
720
            return Camera::Result::WrongArgument;
×
721
        case MavlinkParameterClient::Result::ParamNameTooLong:
×
722
            return Camera::Result::WrongArgument;
×
723
        case MavlinkParameterClient::Result::NotFound:
×
724
            return Camera::Result::WrongArgument;
×
725
        case MavlinkParameterClient::Result::ValueUnsupported:
×
726
            return Camera::Result::WrongArgument;
×
727
        case MavlinkParameterClient::Result::Failed:
×
728
            return Camera::Result::Error;
×
729
        case MavlinkParameterClient::Result::UnknownError:
×
730
            return Camera::Result::Error;
×
731
        default:
×
732
            return Camera::Result::Unknown;
×
733
    }
734
}
735

736
Camera::Result CameraImpl::set_mode(const Camera::Mode mode)
×
737
{
738
    const float mavlink_mode = to_mavlink_camera_mode(mode);
×
739
    auto cmd_set_camera_mode = make_command_set_camera_mode(mavlink_mode);
×
740
    const auto command_result = _system_impl->send_command(cmd_set_camera_mode);
×
741
    const auto camera_result = camera_result_from_command_result(command_result);
×
742

743
    if (camera_result == Camera::Result::Success) {
×
744
        {
745
            std::lock_guard<std::mutex> lock(_mode.mutex);
×
746
            _mode.data = mode;
×
747
        }
748
        notify_mode();
×
749
        if (_camera_definition != nullptr) {
×
750
            save_camera_mode(mavlink_mode);
×
751
        }
752
    }
753

754
    return camera_result;
×
755
}
756

757
void CameraImpl::save_camera_mode(const float mavlink_camera_mode)
×
758
{
759
    if (!std::isfinite(mavlink_camera_mode)) {
×
760
        LogWarn() << "Can't save NAN as camera mode";
×
761
        return;
×
762
    }
763

764
    // If there is a camera definition (which is the case if we are
765
    // in this function, and if CAM_MODE is defined there, then
766
    // we reuse that type. Otherwise, we hardcode it to `uint32_t`.
767
    // Note that it could be that the camera definition defines options
768
    // different than {PHOTO, VIDEO}, in which case the mode received
769
    // from CAMERA_SETTINGS will be wrong. Not sure if it means that
770
    // it should be ignored in that case, but that may be tricky to
771
    // maintain (what if the MAVLink CAMERA_MODE enum evolves?), so
772
    // I am assuming here that in such a case, CAMERA_SETTINGS is
773
    // never sent by the camera.
774
    ParamValue value;
×
775
    if (_camera_definition->get_setting("CAM_MODE", value)) {
×
776
        if (value.is<uint8_t>()) {
×
777
            value.set<uint8_t>(static_cast<uint8_t>(mavlink_camera_mode));
×
778
        } else if (value.is<int8_t>()) {
×
779
            value.set<int8_t>(static_cast<int8_t>(mavlink_camera_mode));
×
780
        } else if (value.is<uint16_t>()) {
×
781
            value.set<uint16_t>(static_cast<uint16_t>(mavlink_camera_mode));
×
782
        } else if (value.is<int16_t>()) {
×
783
            value.set<int16_t>(static_cast<int16_t>(mavlink_camera_mode));
×
784
        } else if (value.is<uint32_t>()) {
×
785
            value.set<uint32_t>(static_cast<uint32_t>(mavlink_camera_mode));
×
786
        } else if (value.is<int32_t>()) {
×
787
            value.set<int32_t>(static_cast<int32_t>(mavlink_camera_mode));
×
788
        } else if (value.is<uint64_t>()) {
×
789
            value.set<uint64_t>(static_cast<uint64_t>(mavlink_camera_mode));
×
790
        } else if (value.is<int64_t>()) {
×
791
            value.set<int64_t>(static_cast<int64_t>(mavlink_camera_mode));
×
792
        } else if (value.is<float>()) {
×
793
            value.set<float>(static_cast<float>(mavlink_camera_mode));
×
794
        } else if (value.is<double>()) {
×
795
            value.set<double>(static_cast<double>(mavlink_camera_mode));
×
796
        }
797
    } else {
798
        value.set<uint32_t>(static_cast<uint32_t>(mavlink_camera_mode));
×
799
    }
800

801
    _camera_definition->set_setting("CAM_MODE", value);
×
802
    refresh_params();
×
803
}
804

805
float CameraImpl::to_mavlink_camera_mode(const Camera::Mode mode) const
×
806
{
807
    switch (mode) {
×
808
        case Camera::Mode::Photo:
×
809
            return CAMERA_MODE_IMAGE;
×
810
        case Camera::Mode::Video:
×
811
            return CAMERA_MODE_VIDEO;
×
812
        default:
×
813
        case Camera::Mode::Unknown:
814
            return NAN;
×
815
    }
816
}
817

818
void CameraImpl::set_mode_async(const Camera::Mode mode, const Camera::ResultCallback& callback)
×
819
{
820
    const auto mavlink_mode = to_mavlink_camera_mode(mode);
×
821
    auto cmd_set_camera_mode = make_command_set_camera_mode(mavlink_mode);
×
822

823
    _system_impl->send_command_async(
×
824
        cmd_set_camera_mode,
825
        [this, callback, mode](MavlinkCommandSender::Result result, float progress) {
×
826
            UNUSED(progress);
×
827
            receive_set_mode_command_result(result, callback, mode);
×
828
        });
×
829
}
×
830

831
Camera::Mode CameraImpl::mode()
×
832
{
833
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
834
    return _mode.data;
×
835
}
836

837
Camera::ModeHandle CameraImpl::subscribe_mode(const Camera::ModeCallback& callback)
×
838
{
839
    std::unique_lock<std::mutex> lock(_mode.mutex);
×
840
    auto handle = _mode.subscription_callbacks.subscribe(callback);
×
841
    lock.unlock();
×
842

843
    notify_mode();
×
844

845
    if (callback) {
×
846
        _system_impl->add_call_every(
×
847
            [this]() { request_camera_settings(); }, 5.0, &_mode.call_every_cookie);
×
848
    } else {
849
        _system_impl->remove_call_every(_mode.call_every_cookie);
×
850
    }
851

852
    return handle;
×
853
}
854

855
void CameraImpl::unsubscribe_mode(Camera::ModeHandle handle)
×
856
{
857
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
858
    _mode.subscription_callbacks.unsubscribe(handle);
×
859
}
×
860

861
bool CameraImpl::interval_valid(float interval_s)
×
862
{
863
    // Reject everything faster than 1000 Hz, as well as negative inputs.
864
    if (interval_s < 0.001f) {
×
865
        LogWarn() << "Invalid interval input";
×
866
        return false;
×
867
    } else {
868
        return true;
×
869
    }
870
}
871

872
void CameraImpl::request_status()
×
873
{
874
    _system_impl->send_command_async(make_command_request_camera_capture_status(), nullptr);
×
875
    _system_impl->send_command_async(make_command_request_storage_info(), nullptr);
×
876
}
×
877

878
Camera::StatusHandle CameraImpl::subscribe_status(const Camera::StatusCallback& callback)
×
879
{
880
    std::lock_guard<std::mutex> lock(_status.mutex);
×
881
    auto handle = _status.subscription_callbacks.subscribe(callback);
×
882

883
    return handle;
×
884
}
885

886
void CameraImpl::unsubscribe_status(Camera::StatusHandle handle)
×
887
{
888
    std::lock_guard<std::mutex> lock(_status.mutex);
×
889
    _status.subscription_callbacks.unsubscribe(handle);
×
890
}
×
891

892
Camera::Status CameraImpl::status()
×
893
{
894
    std::lock_guard<std::mutex> lock(_status.mutex);
×
895
    return _status.data;
×
896
}
897

898
Camera::CaptureInfoHandle
899
CameraImpl::subscribe_capture_info(const Camera::CaptureInfoCallback& callback)
×
900
{
901
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
902
    return _capture_info.callbacks.subscribe(callback);
×
903
}
904

905
void CameraImpl::unsubscribe_capture_info(Camera::CaptureInfoHandle handle)
×
906
{
907
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
908
    _capture_info.callbacks.unsubscribe(handle);
×
909
}
×
910

911
void CameraImpl::process_camera_capture_status(const mavlink_message_t& message)
×
912
{
913
    mavlink_camera_capture_status_t camera_capture_status;
×
914
    mavlink_msg_camera_capture_status_decode(&message, &camera_capture_status);
×
915

916
    // If image_count got smaller, consider that the storage was formatted.
917
    if (camera_capture_status.image_count < _status.image_count) {
×
918
        LogDebug() << "Seems like storage was formatted, setting state accordingly";
×
919
        reset_following_format_storage();
×
920
    }
921

922
    {
923
        std::lock_guard<std::mutex> lock(_status.mutex);
×
924

925
        _status.data.video_on = (camera_capture_status.video_status == 1);
×
926
        _status.data.photo_interval_on =
×
927
            (camera_capture_status.image_status == 2 || camera_capture_status.image_status == 3);
×
928
        _status.received_camera_capture_status = true;
×
929
        _status.data.recording_time_s = float(camera_capture_status.recording_time_ms) / 1e3f;
×
930

931
        _status.image_count = camera_capture_status.image_count;
×
932

933
        if (_status.image_count_at_connection == -1) {
×
934
            _status.image_count_at_connection = camera_capture_status.image_count;
×
935
        }
936
    }
937

938
    check_status();
×
939
}
×
940

941
void CameraImpl::process_storage_information(const mavlink_message_t& message)
×
942
{
943
    mavlink_storage_information_t storage_information;
×
944
    mavlink_msg_storage_information_decode(&message, &storage_information);
×
945

946
    if (storage_information.total_capacity == 0.0f) {
×
947
        // Some MAVLink systems happen to send the STORAGE_INFORMATION message
948
        // to indicate that the camera has a slot for a storage even if there
949
        // is no way to know anything about that storage (e.g. whether or not
950
        // there is an sdcard in the slot).
951
        //
952
        // We consider that a total capacity of 0 means that this is such a
953
        // message, and we don't expect MAVSDK users to leverage it, which is
954
        // why it is ignored.
955
        return;
×
956
    }
957

958
    {
959
        std::lock_guard<std::mutex> lock(_status.mutex);
×
960
        _status.data.storage_status = storage_status_from_mavlink(storage_information.status);
×
961
        _status.data.available_storage_mib = storage_information.available_capacity;
×
962
        _status.data.used_storage_mib = storage_information.used_capacity;
×
963
        _status.data.total_storage_mib = storage_information.total_capacity;
×
964
        _status.data.storage_id = storage_information.storage_id;
×
965
        _status.data.storage_type = storage_type_from_mavlink(storage_information.type);
×
966
        _status.received_storage_information = true;
×
967
    }
968

969
    check_status();
×
970
}
971

972
Camera::Status::StorageStatus
973
CameraImpl::storage_status_from_mavlink(const int storage_status) const
×
974
{
975
    switch (storage_status) {
×
976
        case STORAGE_STATUS_EMPTY:
×
977
            return Camera::Status::StorageStatus::NotAvailable;
×
978
        case STORAGE_STATUS_UNFORMATTED:
×
979
            return Camera::Status::StorageStatus::Unformatted;
×
980
        case STORAGE_STATUS_READY:
×
981
            return Camera::Status::StorageStatus::Formatted;
×
982
            break;
983
        case STORAGE_STATUS_NOT_SUPPORTED:
×
984
            return Camera::Status::StorageStatus::NotSupported;
×
985
        default:
×
986
            LogErr() << "Unknown storage status received.";
×
987
            return Camera::Status::StorageStatus::NotSupported;
×
988
    }
989
}
990

991
Camera::Status::StorageType CameraImpl::storage_type_from_mavlink(const int storage_type) const
×
992
{
993
    switch (storage_type) {
×
994
        default:
×
995
            LogErr() << "Unknown storage_type enum value: " << storage_type;
×
996
        // FALLTHROUGH
997
        case STORAGE_TYPE_UNKNOWN:
×
998
            return mavsdk::Camera::Status::StorageType::Unknown;
×
999
        case STORAGE_TYPE_USB_STICK:
×
1000
            return mavsdk::Camera::Status::StorageType::UsbStick;
×
1001
        case STORAGE_TYPE_SD:
×
1002
            return mavsdk::Camera::Status::StorageType::Sd;
×
1003
        case STORAGE_TYPE_MICROSD:
×
1004
            return mavsdk::Camera::Status::StorageType::Microsd;
×
1005
        case STORAGE_TYPE_HD:
×
1006
            return mavsdk::Camera::Status::StorageType::Hd;
×
1007
        case STORAGE_TYPE_OTHER:
×
1008
            return mavsdk::Camera::Status::StorageType::Other;
×
1009
    }
1010
}
1011

1012
void CameraImpl::process_camera_image_captured(const mavlink_message_t& message)
×
1013
{
1014
    mavlink_camera_image_captured_t image_captured;
×
1015
    mavlink_msg_camera_image_captured_decode(&message, &image_captured);
×
1016

1017
    {
1018
        Camera::CaptureInfo capture_info = {};
×
1019
        capture_info.position.latitude_deg = image_captured.lat / 1e7;
×
1020
        capture_info.position.longitude_deg = image_captured.lon / 1e7;
×
1021
        capture_info.position.absolute_altitude_m = image_captured.alt / 1e3f;
×
1022
        capture_info.position.relative_altitude_m = image_captured.relative_alt / 1e3f;
×
1023
        capture_info.time_utc_us = image_captured.time_utc;
×
1024
        capture_info.attitude_quaternion.w = image_captured.q[0];
×
1025
        capture_info.attitude_quaternion.x = image_captured.q[1];
×
1026
        capture_info.attitude_quaternion.y = image_captured.q[2];
×
1027
        capture_info.attitude_quaternion.z = image_captured.q[3];
×
1028
        capture_info.attitude_euler_angle =
1029
            to_euler_angle_from_quaternion(capture_info.attitude_quaternion);
×
1030
        capture_info.file_url = std::string(image_captured.file_url);
×
1031
        capture_info.is_success = (image_captured.capture_result == 1);
×
1032
        capture_info.index = image_captured.image_index;
×
1033

1034
        _status.photo_list.insert(std::make_pair(image_captured.image_index, capture_info));
×
1035

1036
        _captured_request_cv.notify_all();
×
1037

1038
        std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1039
        // Notify user if a new image has been captured.
1040
        if (_capture_info.last_advertised_image_index < capture_info.index) {
×
1041
            _capture_info.callbacks.queue(
×
1042
                capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1043

1044
            if (_capture_info.last_advertised_image_index != -1) {
×
1045
                // Save captured indices that have been dropped to request later, however, don't
1046
                // do it from the very beginning as there might be many photos from a previous
1047
                // time that we don't want to request.
1048
                for (int i = _capture_info.last_advertised_image_index + 1; i < capture_info.index;
×
1049
                     ++i) {
1050
                    if (_capture_info.missing_image_retries.find(i) ==
×
1051
                        _capture_info.missing_image_retries.end()) {
×
1052
                        _capture_info.missing_image_retries[i] = 0;
×
1053
                    }
1054
                }
1055
            }
1056

1057
            _capture_info.last_advertised_image_index = capture_info.index;
×
1058
        }
1059

1060
        else if (auto it = _capture_info.missing_image_retries.find(capture_info.index);
×
1061
                 it != _capture_info.missing_image_retries.end()) {
×
1062
            _capture_info.callbacks.queue(
×
1063
                capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1064
            _capture_info.missing_image_retries.erase(it);
×
1065
        }
1066
    }
1067
}
×
1068

1069
void CameraImpl::request_missing_capture_info()
×
1070
{
1071
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1072

1073
    for (auto it = _capture_info.missing_image_retries.begin();
×
1074
         it != _capture_info.missing_image_retries.end();
×
1075
         /* ++it */) {
1076
        if (it->second > 3) {
×
1077
            it = _capture_info.missing_image_retries.erase(it);
×
1078
        } else {
1079
            ++it;
×
1080
        }
1081
    }
1082

1083
    if (!_capture_info.missing_image_retries.empty()) {
×
1084
        auto it_lowest_retries = std::min_element(
×
1085
            _capture_info.missing_image_retries.begin(), _capture_info.missing_image_retries.end());
×
1086
        _system_impl->send_command_async(
×
1087
            CameraImpl::make_command_request_camera_image_captured(it_lowest_retries->first),
×
1088
            nullptr);
1089
        it_lowest_retries->second += 1;
×
1090
    }
1091
}
×
1092

1093
Camera::EulerAngle CameraImpl::to_euler_angle_from_quaternion(Camera::Quaternion quaternion)
×
1094
{
1095
    auto& q = quaternion;
×
1096

1097
    // FIXME: This is duplicated from telemetry/math_conversions.cpp.
1098
    Camera::EulerAngle euler_angle;
×
1099
    euler_angle.roll_deg = to_deg_from_rad(
×
1100
        atan2f(2.0f * (q.w * q.x + q.y * q.z), 1.0f - 2.0f * (q.x * q.x + q.y * q.y)));
×
1101

1102
    euler_angle.pitch_deg = to_deg_from_rad(asinf(2.0f * (q.w * q.y - q.z * q.x)));
×
1103
    euler_angle.yaw_deg = to_deg_from_rad(
×
1104
        atan2f(2.0f * (q.w * q.z + q.x * q.y), 1.0f - 2.0f * (q.y * q.y + q.z * q.z)));
×
1105
    return euler_angle;
×
1106
}
1107

1108
void CameraImpl::process_camera_settings(const mavlink_message_t& message)
×
1109
{
1110
    mavlink_camera_settings_t camera_settings;
×
1111
    mavlink_msg_camera_settings_decode(&message, &camera_settings);
×
1112

1113
    {
1114
        std::lock_guard<std::mutex> lock(_mode.mutex);
×
1115
        _mode.data = to_camera_mode(camera_settings.mode_id);
×
1116
    }
1117
    notify_mode();
×
1118

1119
    if (_camera_definition) {
×
1120
        // This "parameter" needs to be manually set.
1121
        save_camera_mode(camera_settings.mode_id);
×
1122
    }
1123
}
×
1124

1125
Camera::Mode CameraImpl::to_camera_mode(const uint8_t mavlink_camera_mode) const
×
1126
{
1127
    switch (mavlink_camera_mode) {
×
1128
        case CAMERA_MODE_IMAGE:
×
1129
            return Camera::Mode::Photo;
×
1130
        case CAMERA_MODE_VIDEO:
×
1131
            return Camera::Mode::Video;
×
1132
        default:
×
1133
            return Camera::Mode::Unknown;
×
1134
    }
1135
}
1136

1137
void CameraImpl::process_camera_information(const mavlink_message_t& message)
×
1138
{
1139
    mavlink_camera_information_t camera_information;
×
1140
    mavlink_msg_camera_information_decode(&message, &camera_information);
×
1141

1142
    // Make sure all strings are zero terminated, so we don't overrun anywhere.
1143
    camera_information.vendor_name[sizeof(camera_information.vendor_name) - 1] = '\0';
×
1144
    camera_information.model_name[sizeof(camera_information.model_name) - 1] = '\0';
×
1145
    camera_information.cam_definition_uri[sizeof(camera_information.cam_definition_uri) - 1] = '\0';
×
1146

1147
    std::lock_guard<std::mutex> lock(_information.mutex);
×
1148

1149
    _information.data.vendor_name = (char*)(camera_information.vendor_name);
×
1150
    _information.data.model_name = (char*)(camera_information.model_name);
×
1151
    _information.data.focal_length_mm = camera_information.focal_length;
×
1152
    _information.data.horizontal_sensor_size_mm = camera_information.sensor_size_h;
×
1153
    _information.data.vertical_sensor_size_mm = camera_information.sensor_size_v;
×
1154
    _information.data.horizontal_resolution_px = camera_information.resolution_h;
×
1155
    _information.data.vertical_resolution_px = camera_information.resolution_v;
×
1156

1157
    _information.subscription_callbacks.queue(
×
1158
        _information.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1159

1160
    if (should_fetch_camera_definition(camera_information.cam_definition_uri)) {
×
1161
        _is_fetching_camera_definition = true;
×
1162

1163
        std::thread([this, camera_information]() {
×
1164
            std::string content{};
×
1165
            const auto has_succeeded = fetch_camera_definition(camera_information, content);
×
1166

1167
            if (has_succeeded) {
×
1168
                LogDebug() << "Successfully loaded camera definition";
×
1169

1170
                if (_camera_definition_callback) {
×
1171
                    _system_impl->call_user_callback(
×
1172
                        [this]() { _camera_definition_callback(true); });
1173
                }
1174

1175
                _camera_definition.reset(new CameraDefinition());
×
1176
                _camera_definition->load_string(content);
×
1177
                refresh_params();
×
1178
            } else {
1179
                LogDebug() << "Failed to fetch camera definition!";
×
1180

1181
                if (++_camera_definition_fetch_count >= 3) {
×
1182
                    LogWarn() << "Giving up fetching the camera definition";
×
1183

1184
                    std::lock_guard<std::mutex> thread_lock(_information.mutex);
×
1185
                    _has_camera_definition_timed_out = true;
×
1186

1187
                    if (_camera_definition_callback) {
×
1188
                        _system_impl->call_user_callback(
×
1189
                            [this]() { _camera_definition_callback(false); });
1190
                    }
1191
                }
1192
            }
1193

1194
            std::lock_guard<std::mutex> thread_lock(_information.mutex);
×
1195
            _is_fetching_camera_definition = false;
×
1196
        }).detach();
×
1197
    }
1198
}
×
1199

1200
bool CameraImpl::should_fetch_camera_definition(const std::string& uri) const
×
1201
{
1202
    return !uri.empty() && !_camera_definition && !_is_fetching_camera_definition &&
×
1203
           !_has_camera_definition_timed_out;
×
1204
}
1205

1206
bool CameraImpl::fetch_camera_definition(
×
1207
    const mavlink_camera_information_t& camera_information, std::string& camera_definition_out)
1208
{
1209
    auto download_succeeded =
1210
        download_definition_file(camera_information.cam_definition_uri, camera_definition_out);
×
1211

1212
    if (download_succeeded) {
×
1213
        return true;
×
1214
    }
1215

1216
    return load_stored_definition(camera_information, camera_definition_out);
×
1217
}
1218

1219
bool CameraImpl::download_definition_file(
×
1220
    const std::string& uri, std::string& camera_definition_out)
1221
{
1222
    HttpLoader http_loader;
×
1223
    LogInfo() << "Downloading camera definition from: " << uri;
×
1224
    if (!http_loader.download_text_sync(uri, camera_definition_out)) {
×
1225
        LogErr() << "Failed to download camera definition.";
×
1226
        return false;
×
1227
    }
1228

1229
    return true;
×
1230
}
1231

1232
bool CameraImpl::load_stored_definition(
×
1233
    const mavlink_camera_information_t& camera_information, std::string& camera_definition_out)
1234
{
1235
    // TODO: we might also try to support the correct version of the xml files.
1236

1237
    const auto vendor_name = std::string(
×
1238
        reinterpret_cast<const char*>(std::begin(camera_information.vendor_name)),
×
1239
        reinterpret_cast<const char*>(std::end(camera_information.vendor_name)));
×
1240

1241
    const auto model_name = std::string(
×
1242
        reinterpret_cast<const char*>(std::begin(camera_information.model_name)),
×
1243
        reinterpret_cast<const char*>(std::end(camera_information.model_name)));
×
1244

1245
    if (vendor_name == "Yuneec") {
×
1246
        if (model_name == "E90") {
×
1247
            LogInfo() << "Using cached file for Yuneec E90.";
×
1248
            camera_definition_out = e90xml;
×
1249
            return true;
×
1250
        } else if (model_name == "E50") {
×
1251
            LogInfo() << "Using cached file for Yuneec E50.";
×
1252
            camera_definition_out = e50xml;
×
1253
            return true;
×
1254
        } else if (model_name == "CGOET") {
×
1255
            LogInfo() << "Using cached file for Yuneec ET.";
×
1256
            camera_definition_out = cgoetxml;
×
1257
            return true;
×
1258
        } else if (model_name == "E10T") {
×
1259
            LogInfo() << "Using cached file for Yuneec E10T.";
×
1260
            camera_definition_out = e10txml;
×
1261
            return true;
×
1262
        } else if (model_name == "E30Z") {
×
1263
            LogInfo() << "Using cached file for Yuneec E30Z.";
×
1264
            camera_definition_out = e30zxml;
×
1265
            return true;
×
1266
        }
1267
    } else if (vendor_name == "Sony") {
×
1268
        if (model_name == "ILCE-7RM4") {
×
1269
            LogInfo() << "Using cached file for Sony ILCE-7RM4.";
×
1270
            camera_definition_out = ILCE7RM4xml;
×
1271
            return true;
×
1272
        }
1273
    }
1274

1275
    return false;
×
1276
}
1277

1278
void CameraImpl::process_video_information(const mavlink_message_t& message)
×
1279
{
1280
    mavlink_video_stream_information_t received_video_info;
×
1281
    mavlink_msg_video_stream_information_decode(&message, &received_video_info);
×
1282

1283
    {
1284
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1285
        // TODO: use stream_id and count
1286
        _video_stream_info.data.status =
×
1287
            (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
×
1288
                 Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1289
                 Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1290
        _video_stream_info.data.spectrum =
×
1291
            (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
×
1292
                 Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1293
                 Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1294

1295
        auto& video_stream_info = _video_stream_info.data.settings;
×
1296
        video_stream_info.frame_rate_hz = received_video_info.framerate;
×
1297
        video_stream_info.horizontal_resolution_pix = received_video_info.resolution_h;
×
1298
        video_stream_info.vertical_resolution_pix = received_video_info.resolution_v;
×
1299
        video_stream_info.bit_rate_b_s = received_video_info.bitrate;
×
1300
        video_stream_info.rotation_deg = received_video_info.rotation;
×
1301
        video_stream_info.horizontal_fov_deg = static_cast<float>(received_video_info.hfov);
×
1302
        video_stream_info.uri = received_video_info.uri;
×
1303
        _video_stream_info.available = true;
×
1304
    }
1305

1306
    notify_video_stream_info();
×
1307
}
×
1308

1309
void CameraImpl::process_video_stream_status(const mavlink_message_t& message)
×
1310
{
1311
    mavlink_video_stream_status_t received_video_stream_status;
×
1312
    mavlink_msg_video_stream_status_decode(&message, &received_video_stream_status);
×
1313
    {
1314
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1315
        _video_stream_info.data.status =
×
1316
            (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
×
1317
                 Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1318
                 Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1319
        _video_stream_info.data.spectrum =
×
1320
            (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
×
1321
                 Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1322
                 Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1323

1324
        auto& video_stream_info = _video_stream_info.data.settings;
×
1325
        video_stream_info.frame_rate_hz = received_video_stream_status.framerate;
×
1326
        video_stream_info.horizontal_resolution_pix = received_video_stream_status.resolution_h;
×
1327
        video_stream_info.vertical_resolution_pix = received_video_stream_status.resolution_v;
×
1328
        video_stream_info.bit_rate_b_s = received_video_stream_status.bitrate;
×
1329
        video_stream_info.rotation_deg = received_video_stream_status.rotation;
×
1330
        video_stream_info.horizontal_fov_deg =
×
1331
            static_cast<float>(received_video_stream_status.hfov);
×
1332
        _video_stream_info.available = true;
×
1333
    }
1334

1335
    notify_video_stream_info();
×
1336
}
×
1337

1338
void CameraImpl::process_flight_information(const mavlink_message_t& message)
×
1339
{
1340
    mavlink_flight_information_t flight_information;
×
1341
    mavlink_msg_flight_information_decode(&message, &flight_information);
×
1342

1343
    std::stringstream folder_name_stream;
×
1344
    {
1345
        std::lock_guard<std::mutex> information_lock(_information.mutex);
×
1346

1347
        // For Yuneec cameras, the folder names can be derived from the flight ID,
1348
        // starting at 100 up to 999.
1349
        if (_information.data.vendor_name == "Yuneec" && _information.data.model_name == "E90") {
×
1350
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "E90HD";
×
1351
        } else if (
×
1352
            _information.data.vendor_name == "Yuneec" && _information.data.model_name == "E50") {
×
1353
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "E50HD";
×
1354
        } else if (
×
1355
            _information.data.vendor_name == "Yuneec" && _information.data.model_name == "CGOET") {
×
1356
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "CGOET";
×
1357
        } else if (
×
1358
            _information.data.vendor_name == "Yuneec" && _information.data.model_name == "E10T") {
×
1359
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "E10T";
×
1360
        } else {
1361
            // Folder name unknown
1362
        }
1363
    }
1364

1365
    {
1366
        std::lock_guard<std::mutex> lock(_status.mutex);
×
1367
        _status.data.media_folder_name = folder_name_stream.str();
×
1368
    }
1369
}
×
1370

1371
void CameraImpl::notify_video_stream_info()
×
1372
{
1373
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1374

1375
    _video_stream_info.subscription_callbacks.queue(
×
1376
        _video_stream_info.data,
×
1377
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1378
}
×
1379

1380
void CameraImpl::check_status()
×
1381
{
1382
    std::lock_guard<std::mutex> lock(_status.mutex);
×
1383

1384
    if (_status.received_camera_capture_status && _status.received_storage_information) {
×
1385
        _status.subscription_callbacks.queue(
×
1386
            _status.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1387

1388
        _status.received_camera_capture_status = false;
×
1389
        _status.received_storage_information = false;
×
1390
    }
1391
}
×
1392

1393
void CameraImpl::receive_command_result(
×
1394
    MavlinkCommandSender::Result command_result, const Camera::ResultCallback& callback)
1395
{
1396
    Camera::Result camera_result = camera_result_from_command_result(command_result);
×
1397

1398
    if (callback) {
×
1399
        _system_impl->call_user_callback([callback, camera_result]() { callback(camera_result); });
×
1400
    }
1401
}
×
1402

1403
void CameraImpl::receive_set_mode_command_result(
×
1404
    const MavlinkCommandSender::Result command_result,
1405
    const Camera::ResultCallback callback,
1406
    const Camera::Mode mode)
1407
{
1408
    Camera::Result camera_result = camera_result_from_command_result(command_result);
×
1409

1410
    if (callback) {
×
1411
        const auto temp_callback = callback;
×
1412
        _system_impl->call_user_callback(
×
1413
            [temp_callback, camera_result]() { temp_callback(camera_result); });
1414
    }
1415

1416
    if (command_result == MavlinkCommandSender::Result::Success && _camera_definition) {
×
1417
        // This "parameter" needs to be manually set.
1418
        {
1419
            std::lock_guard<std::mutex> lock(_mode.mutex);
×
1420
            _mode.data = mode;
×
1421
        }
1422

1423
        const auto mavlink_mode = to_mavlink_camera_mode(mode);
×
1424

1425
        if (std::isnan(mavlink_mode)) {
×
1426
            LogWarn() << "Unknown camera mode";
×
1427
            return;
×
1428
        }
1429

1430
        notify_mode();
×
1431
        save_camera_mode(mavlink_mode);
×
1432
    }
1433
}
1434

1435
void CameraImpl::notify_mode()
×
1436
{
1437
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
1438

1439
    _mode.subscription_callbacks.queue(
×
1440
        _mode.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1441
}
×
1442

1443
bool CameraImpl::get_possible_setting_options(std::vector<std::string>& settings)
×
1444
{
1445
    settings.clear();
×
1446

1447
    if (!_camera_definition) {
×
1448
        LogWarn() << "Error: no camera definition available yet";
×
1449
        return false;
×
1450
    }
1451

1452
    std::unordered_map<std::string, ParamValue> cd_settings{};
×
1453
    _camera_definition->get_possible_settings(cd_settings);
×
1454

1455
    for (const auto& cd_setting : cd_settings) {
×
1456
        if (cd_setting.first == "CAM_MODE") {
×
1457
            // We ignore the mode param.
1458
            continue;
×
1459
        }
1460

1461
        settings.push_back(cd_setting.first);
×
1462
    }
1463

1464
    return settings.size() > 0;
×
1465
}
1466

1467
bool CameraImpl::get_possible_options(
×
1468
    const std::string& setting_id, std::vector<Camera::Option>& options)
1469
{
1470
    options.clear();
×
1471

1472
    if (!_camera_definition) {
×
1473
        LogWarn() << "Error: no camera definition available yet";
×
1474
        return false;
×
1475
    }
1476

1477
    std::vector<ParamValue> values;
×
1478
    if (!_camera_definition->get_possible_options(setting_id, values)) {
×
1479
        return false;
×
1480
    }
1481

1482
    for (const auto& value : values) {
×
1483
        std::stringstream ss{};
×
1484
        ss << value;
×
1485
        Camera::Option option{};
×
1486
        option.option_id = ss.str();
×
1487
        if (!is_setting_range(setting_id)) {
×
1488
            get_option_str(setting_id, option.option_id, option.option_description);
×
1489
        }
1490
        options.push_back(option);
×
1491
    }
1492

1493
    return options.size() > 0;
×
1494
}
1495

1496
bool CameraImpl::is_setting_range(const std::string& setting_id)
×
1497
{
1498
    return _camera_definition->is_setting_range(setting_id);
×
1499
}
1500

1501
Camera::Result CameraImpl::set_setting(Camera::Setting setting)
×
1502
{
1503
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1504
    auto ret = prom->get_future();
×
1505

1506
    set_setting_async(setting, [&prom](Camera::Result result) { prom->set_value(result); });
×
1507

1508
    return ret.get();
×
1509
}
1510

1511
void CameraImpl::set_setting_async(Camera::Setting setting, const Camera::ResultCallback callback)
×
1512
{
1513
    set_option_async(setting.setting_id, setting.option, callback);
×
1514
}
×
1515

1516
void CameraImpl::set_option_async(
×
1517
    const std::string& setting_id,
1518
    const Camera::Option& option,
1519
    const Camera::ResultCallback& callback)
1520
{
1521
    if (!_camera_definition) {
×
1522
        LogWarn() << "Error: no camera defnition available yet.";
×
1523
        if (callback) {
×
1524
            const auto temp_callback = callback;
×
1525
            _system_impl->call_user_callback(
×
1526
                [temp_callback]() { temp_callback(Camera::Result::Error); });
1527
        }
1528
        return;
×
1529
    }
1530

1531
    // We get it first so that we have the type of the param value.
1532
    ParamValue value;
×
1533

1534
    if (_camera_definition->is_setting_range(setting_id)) {
×
1535
        // TODO: Get type from minimum.
1536
        std::vector<ParamValue> all_values;
×
1537
        if (!_camera_definition->get_all_options(setting_id, all_values)) {
×
1538
            if (callback) {
×
1539
                LogErr() << "Could not get all options to get type for range param.";
×
1540
                const auto temp_callback = callback;
×
1541
                _system_impl->call_user_callback(
×
1542
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1543
            }
1544
            return;
×
1545
        }
1546

1547
        if (all_values.size() == 0) {
×
1548
            if (callback) {
×
1549
                LogErr() << "Could not get any options to get type for range param.";
×
1550
                const auto temp_callback = callback;
×
1551
                _system_impl->call_user_callback(
×
1552
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1553
            }
1554
            return;
×
1555
        }
1556
        value = all_values[0];
×
1557
        // Now re-use that type.
1558
        // FIXME: this is quite ugly, we should do better than that.
1559
        if (!value.set_as_same_type(option.option_id)) {
×
1560
            if (callback) {
×
1561
                LogErr() << "Could not set option value to given type.";
×
1562
                const auto temp_callback = callback;
×
1563
                _system_impl->call_user_callback(
×
1564
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1565
            }
1566
            return;
×
1567
        }
1568

1569
    } else {
1570
        if (!_camera_definition->get_option_value(setting_id, option.option_id, value)) {
×
1571
            if (callback) {
×
1572
                LogErr() << "Could not get option value.";
×
1573
                const auto temp_callback = callback;
×
1574
                _system_impl->call_user_callback(
×
1575
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1576
            }
1577
            return;
×
1578
        }
1579

1580
        std::vector<ParamValue> possible_values;
×
1581
        _camera_definition->get_possible_options(setting_id, possible_values);
×
1582
        bool allowed = false;
×
1583
        for (const auto& possible_value : possible_values) {
×
1584
            if (value == possible_value) {
×
1585
                allowed = true;
×
1586
            }
1587
        }
1588
        if (!allowed) {
×
1589
            LogErr() << "Setting " << setting_id << "(" << option.option_id << ") not allowed";
×
1590
            if (callback) {
×
1591
                const auto temp_callback = callback;
×
1592
                _system_impl->call_user_callback(
×
1593
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1594
            }
1595
            return;
×
1596
        }
1597
    }
1598

1599
    _system_impl->set_param_async(
×
1600
        setting_id,
1601
        value,
1602
        [this, callback, setting_id, value](MavlinkParameterClient::Result result) {
×
1603
            if (result == MavlinkParameterClient::Result::Success) {
×
1604
                if (!this->_camera_definition) {
×
1605
                    if (callback) {
×
1606
                        const auto temp_callback = callback;
×
1607
                        _system_impl->call_user_callback(
×
1608
                            [temp_callback]() { temp_callback(Camera::Result::Error); });
1609
                    }
1610
                    return;
×
1611
                }
1612

1613
                if (!_camera_definition->set_setting(setting_id, value)) {
×
1614
                    if (callback) {
×
1615
                        const auto temp_callback = callback;
×
1616
                        _system_impl->call_user_callback(
×
1617
                            [temp_callback]() { temp_callback(Camera::Result::Error); });
1618
                    }
1619
                    return;
×
1620
                }
1621

1622
                if (callback) {
×
1623
                    const auto temp_callback = callback;
×
1624
                    _system_impl->call_user_callback(
×
1625
                        [temp_callback]() { temp_callback(Camera::Result::Success); });
1626
                }
1627

1628
                // FIXME: We are already holding the lock when this lambda is run and need to
1629
                //        schedule the refresh_params() for later.
1630
                //        We (ab)use the thread pool for the user callbacks for this.
1631
                _system_impl->call_user_callback([this]() { refresh_params(); });
×
1632
            } else {
1633
                if (callback) {
×
1634
                    const auto temp_callback = callback;
×
1635
                    _system_impl->call_user_callback([temp_callback, result]() {
×
1636
                        temp_callback(camera_result_from_parameter_result(result));
1637
                    });
1638
                }
1639
            }
1640
        },
1641
        this,
1642
        static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA),
×
1643
        true);
1644
}
1645

1646
void CameraImpl::get_setting_async(
×
1647
    Camera::Setting setting, const Camera::GetSettingCallback callback)
1648
{
1649
    get_option_async(
×
1650
        setting.setting_id,
×
1651
        [this, setting, callback](Camera::Result result, const Camera::Option& option) {
×
1652
            Camera::Setting new_setting{};
×
1653
            new_setting.option = option;
×
1654
            if (callback) {
×
1655
                const auto temp_callback = callback;
×
1656
                _system_impl->call_user_callback(
×
1657
                    [temp_callback, result, new_setting]() { temp_callback(result, new_setting); });
1658
            }
1659
        });
×
1660
}
×
1661

1662
std::pair<Camera::Result, Camera::Setting> CameraImpl::get_setting(Camera::Setting setting)
×
1663
{
1664
    auto prom = std::make_shared<std::promise<std::pair<Camera::Result, Camera::Setting>>>();
×
1665
    auto ret = prom->get_future();
×
1666

1667
    get_setting_async(setting, [&prom](Camera::Result result, const Camera::Setting& new_setting) {
×
1668
        prom->set_value(std::make_pair<>(result, new_setting));
×
1669
    });
×
1670

1671
    return ret.get();
×
1672
}
1673

1674
Camera::Result CameraImpl::get_option(const std::string& setting_id, Camera::Option& option)
×
1675
{
1676
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1677
    auto ret = prom->get_future();
×
1678

1679
    get_option_async(
×
1680
        setting_id, [prom, &option](Camera::Result result, const Camera::Option& option_gotten) {
×
1681
            prom->set_value(result);
×
1682
            if (result == Camera::Result::Success) {
×
1683
                option = option_gotten;
×
1684
            }
1685
        });
×
1686

1687
    auto status = ret.wait_for(std::chrono::seconds(1));
×
1688

1689
    if (status == std::future_status::ready) {
×
1690
        return Camera::Result::Success;
×
1691
    } else {
1692
        return Camera::Result::Timeout;
×
1693
    }
1694
}
1695

1696
void CameraImpl::get_option_async(
×
1697
    const std::string& setting_id,
1698
    const std::function<void(Camera::Result, const Camera::Option&)>& callback)
1699
{
1700
    if (!_camera_definition) {
×
1701
        LogWarn() << "Error: no camera defnition available yet.";
×
1702
        if (callback) {
×
1703
            Camera::Option empty_option{};
×
1704
            const auto temp_callback = callback;
×
1705
            _system_impl->call_user_callback([temp_callback, empty_option]() {
×
1706
                temp_callback(Camera::Result::Error, empty_option);
1707
            });
1708
        }
1709
        return;
×
1710
    }
1711

1712
    ParamValue value;
×
1713
    // We should have this cached and don't need to get the param.
1714
    if (_camera_definition->get_setting(setting_id, value)) {
×
1715
        if (callback) {
×
1716
            Camera::Option new_option{};
×
1717
            new_option.option_id = value.get_string();
×
1718
            if (!is_setting_range(setting_id)) {
×
1719
                get_option_str(setting_id, new_option.option_id, new_option.option_description);
×
1720
            }
1721
            const auto temp_callback = callback;
×
1722
            _system_impl->call_user_callback([temp_callback, new_option]() {
×
1723
                temp_callback(Camera::Result::Success, new_option);
1724
            });
1725
        }
1726
    } else {
1727
        // If this still happens, we request the param, but also complain.
1728
        LogWarn() << "Setting '" << setting_id << "' not found.";
×
1729
        if (callback) {
×
1730
            Camera::Option no_option{};
×
1731
            const auto temp_callback = callback;
×
1732
            _system_impl->call_user_callback(
×
1733
                [temp_callback, no_option]() { temp_callback(Camera::Result::Error, no_option); });
1734
        }
1735
    }
1736
}
1737

1738
Camera::CurrentSettingsHandle
1739
CameraImpl::subscribe_current_settings(const Camera::CurrentSettingsCallback& callback)
×
1740
{
1741
    std::unique_lock<std::mutex> lock(_subscribe_current_settings.mutex);
×
1742
    auto handle = _subscribe_current_settings.callbacks.subscribe(callback);
×
1743
    lock.unlock();
×
1744

1745
    notify_current_settings();
×
1746
    return handle;
×
1747
}
1748

1749
void CameraImpl::unsubscribe_current_settings(Camera::CurrentSettingsHandle handle)
×
1750
{
1751
    std::lock_guard<std::mutex> lock(_subscribe_current_settings.mutex);
×
1752
    _subscribe_current_settings.callbacks.unsubscribe(handle);
×
1753
}
×
1754

1755
Camera::PossibleSettingOptionsHandle CameraImpl::subscribe_possible_setting_options(
×
1756
    const Camera::PossibleSettingOptionsCallback& callback)
1757
{
1758
    std::unique_lock<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
1759
    auto handle = _subscribe_possible_setting_options.callbacks.subscribe(callback);
×
1760
    lock.unlock();
×
1761

1762
    notify_possible_setting_options();
×
1763
    return handle;
×
1764
}
1765

1766
void CameraImpl::unsubscribe_possible_setting_options(Camera::PossibleSettingOptionsHandle handle)
×
1767
{
1768
    std::lock_guard<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
1769
    _subscribe_possible_setting_options.callbacks.unsubscribe(handle);
×
1770
}
×
1771

1772
void CameraImpl::notify_current_settings()
×
1773
{
1774
    std::lock_guard<std::mutex> lock(_subscribe_current_settings.mutex);
×
1775

1776
    if (_subscribe_current_settings.callbacks.empty()) {
×
1777
        return;
×
1778
    }
1779

1780
    if (!_camera_definition) {
×
1781
        LogErr() << "notify_current_settings has no camera definition";
×
1782
        return;
×
1783
    }
1784

1785
    std::vector<Camera::Setting> current_settings{};
×
1786
    std::vector<std::string> possible_setting_options{};
×
1787
    if (!get_possible_setting_options(possible_setting_options)) {
×
1788
        LogErr() << "Could not get possible settings in current options subscription.";
×
1789
        return;
×
1790
    }
1791

1792
    for (auto& possible_setting : possible_setting_options) {
×
1793
        // use the cache for this, presumably we updated it right before.
1794
        ParamValue value;
×
1795
        if (_camera_definition->get_setting(possible_setting, value)) {
×
1796
            Camera::Setting setting{};
×
1797
            setting.setting_id = possible_setting;
×
1798
            setting.is_range = is_setting_range(possible_setting);
×
1799
            get_setting_str(setting.setting_id, setting.setting_description);
×
1800
            setting.option.option_id = value.get_string();
×
1801
            if (!is_setting_range(possible_setting)) {
×
1802
                get_option_str(
×
1803
                    setting.setting_id,
1804
                    setting.option.option_id,
1805
                    setting.option.option_description);
1806
            }
1807
            current_settings.push_back(setting);
×
1808
        }
1809
    }
1810

1811
    _subscribe_current_settings.callbacks.queue(
×
1812
        current_settings, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1813
}
1814

1815
void CameraImpl::notify_possible_setting_options()
×
1816
{
1817
    std::lock_guard<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
1818

1819
    if (_subscribe_possible_setting_options.callbacks.empty()) {
×
1820
        return;
×
1821
    }
1822

1823
    if (!_camera_definition) {
×
1824
        LogErr() << "notify_possible_setting_options has no camera definition";
×
1825
        return;
×
1826
    }
1827

1828
    auto setting_options = possible_setting_options();
×
1829
    if (setting_options.size() == 0) {
×
1830
        return;
×
1831
    }
1832

1833
    _subscribe_possible_setting_options.callbacks.queue(
×
1834
        setting_options, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1835
}
1836

1837
std::vector<Camera::SettingOptions> CameraImpl::possible_setting_options()
×
1838
{
1839
    std::vector<Camera::SettingOptions> results{};
×
1840

1841
    std::vector<std::string> possible_settings{};
×
1842
    if (!get_possible_setting_options(possible_settings)) {
×
1843
        LogErr() << "Could not get possible settings.";
×
1844
        return results;
×
1845
    }
1846

1847
    for (auto& possible_setting : possible_settings) {
×
1848
        Camera::SettingOptions setting_options{};
×
1849
        setting_options.setting_id = possible_setting;
×
1850
        setting_options.is_range = _camera_definition->is_setting_range(possible_setting);
×
1851
        get_setting_str(setting_options.setting_id, setting_options.setting_description);
×
1852
        get_possible_options(possible_setting, setting_options.options);
×
1853
        results.push_back(setting_options);
×
1854
    }
1855

1856
    return results;
1857
}
1858

1859
void CameraImpl::refresh_params()
×
1860
{
1861
    if (!_camera_definition) {
×
1862
        return;
×
1863
    }
1864

1865
    std::vector<std::pair<std::string, ParamValue>> params;
×
1866
    _camera_definition->get_unknown_params(params);
×
1867
    if (params.size() == 0) {
×
1868
        // We're assuming that we changed one option and this did not cause
1869
        // any other possible settings to change. However, we still would
1870
        // like to notify the current settings with this one change.
1871
        notify_current_settings();
×
1872
        notify_possible_setting_options();
×
1873
        return;
×
1874
    }
1875

1876
    unsigned count = 0;
×
1877
    for (const auto& param : params) {
×
1878
        const std::string& param_name = param.first;
×
1879
        const ParamValue& param_value_type = param.second;
×
1880
        const bool is_last = (count == params.size() - 1);
×
1881
        _system_impl->get_param_async(
×
1882
            param_name,
1883
            param_value_type,
1884
            [param_name, is_last, this](MavlinkParameterClient::Result result, ParamValue value) {
×
1885
                if (result != MavlinkParameterClient::Result::Success) {
×
1886
                    return;
×
1887
                }
1888
                // We need to check again by the time this callback runs
1889
                if (!this->_camera_definition) {
×
1890
                    return;
×
1891
                }
1892

1893
                if (!this->_camera_definition->set_setting(param_name, value)) {
×
1894
                    return;
×
1895
                }
1896

1897
                if (is_last) {
×
1898
                    notify_current_settings();
×
1899
                    notify_possible_setting_options();
×
1900
                }
1901
            },
1902
            this,
1903
            static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA),
×
1904
            true);
1905
        ++count;
×
1906
    }
1907
}
1908

1909
void CameraImpl::invalidate_params()
×
1910
{
1911
    if (!_camera_definition) {
×
1912
        return;
×
1913
    }
1914

1915
    _camera_definition->set_all_params_unknown();
×
1916
}
1917

1918
bool CameraImpl::get_setting_str(const std::string& setting_id, std::string& description)
×
1919
{
1920
    if (!_camera_definition) {
×
1921
        return false;
×
1922
    }
1923

1924
    return _camera_definition->get_setting_str(setting_id, description);
×
1925
}
1926

1927
bool CameraImpl::get_option_str(
×
1928
    const std::string& setting_id, const std::string& option_id, std::string& description)
1929
{
1930
    if (!_camera_definition) {
×
1931
        return false;
×
1932
    }
1933

1934
    return _camera_definition->get_option_str(setting_id, option_id, description);
×
1935
}
1936

1937
void CameraImpl::request_camera_settings()
×
1938
{
1939
    auto command_camera_settings = make_command_request_camera_settings();
×
1940
    _system_impl->send_command_async(command_camera_settings, nullptr);
×
1941
}
×
1942

1943
void CameraImpl::request_flight_information()
×
1944
{
1945
    auto command_flight_information = make_command_request_flight_information();
×
1946
    _system_impl->send_command_async(command_flight_information, nullptr);
×
1947
}
×
1948

1949
void CameraImpl::request_camera_information()
×
1950
{
1951
    auto command_camera_info = make_command_request_camera_info();
×
1952
    _system_impl->send_command_async(command_camera_info, nullptr);
×
1953
}
×
1954

1955
Camera::Result CameraImpl::format_storage()
×
1956
{
1957
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1958
    auto ret = prom->get_future();
×
1959

1960
    format_storage_async([prom](Camera::Result result) { prom->set_value(result); });
×
1961

1962
    return ret.get();
×
1963
}
1964

1965
void CameraImpl::format_storage_async(Camera::ResultCallback callback)
×
1966
{
1967
    MavlinkCommandSender::CommandLong cmd_format{};
×
1968

1969
    cmd_format.command = MAV_CMD_STORAGE_FORMAT;
×
1970
    cmd_format.params.maybe_param1 = 1.0f; // storage ID
×
1971
    cmd_format.params.maybe_param2 = 1.0f; // format
×
1972
    cmd_format.params.maybe_param3 = 1.0f; // clear
×
1973
    cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
1974

1975
    _system_impl->send_command_async(
×
1976
        cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
×
1977
            UNUSED(progress);
×
1978

1979
            receive_command_result(result, [this, callback](Camera::Result camera_result) {
×
1980
                if (camera_result == Camera::Result::Success) {
×
1981
                    reset_following_format_storage();
×
1982
                }
1983

1984
                callback(camera_result);
×
1985
            });
×
1986
        });
×
1987
}
×
1988

1989
void CameraImpl::reset_following_format_storage()
×
1990
{
1991
    {
1992
        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
1993
        _status.photo_list.clear();
×
1994
        _status.image_count = 0;
×
1995
        _status.image_count_at_connection = 0;
×
1996
    }
1997
    {
1998
        std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1999
        _capture_info.last_advertised_image_index = -1;
×
2000
        _capture_info.missing_image_retries.clear();
×
2001
    }
2002
}
×
2003

2004
std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>
2005
CameraImpl::list_photos(Camera::PhotosRange photos_range)
×
2006
{
2007
    std::promise<std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>> prom;
×
2008
    auto ret = prom.get_future();
×
2009

2010
    list_photos_async(
×
2011
        photos_range, [&prom](Camera::Result result, std::vector<Camera::CaptureInfo> photo_list) {
×
2012
            prom.set_value(std::make_pair(result, photo_list));
×
2013
        });
×
2014

2015
    return ret.get();
×
2016
}
2017

2018
void CameraImpl::list_photos_async(
×
2019
    Camera::PhotosRange photos_range, const Camera::ListPhotosCallback callback)
2020
{
2021
    if (!callback) {
×
2022
        LogWarn() << "Trying to get a photo list with a null callback, ignoring...";
×
2023
        return;
×
2024
    }
2025

2026
    {
2027
        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2028

2029
        if (_status.is_fetching_photos) {
×
2030
            _system_impl->call_user_callback([callback]() {
×
2031
                callback(Camera::Result::Busy, std::vector<Camera::CaptureInfo>{});
2032
            });
2033
            return;
×
2034
        } else {
2035
            _status.is_fetching_photos = true;
×
2036
        }
2037

2038
        if (_status.image_count == -1) {
×
2039
            LogErr() << "Cannot list photos: camera status has not been received yet!";
×
2040
            _status.is_fetching_photos = false;
×
2041
            _system_impl->call_user_callback([callback]() {
×
2042
                callback(Camera::Result::Error, std::vector<Camera::CaptureInfo>{});
2043
            });
2044
            return;
×
2045
        }
2046
    }
2047

2048
    const int start_index = [this, photos_range]() {
×
2049
        switch (photos_range) {
×
2050
            case Camera::PhotosRange::SinceConnection:
×
2051
                return _status.image_count_at_connection;
×
2052
            case Camera::PhotosRange::All:
×
2053
            // FALLTHROUGH
2054
            default:
2055
                return 0;
×
2056
        }
2057
    }();
×
2058

2059
    std::thread([this, start_index, callback]() {
×
2060
        std::unique_lock<std::mutex> capture_request_lock(_captured_request_mutex);
×
2061

2062
        for (int i = start_index; i < _status.image_count; i++) {
×
2063
            // In case the vehicle sends capture info, but not those we are asking, we do not
2064
            // want to loop infinitely. The safety_count is here to abort if this happens.
2065
            auto safety_count = 0;
×
2066
            const auto safety_count_boundary = 10;
×
2067

2068
            while (_status.photo_list.find(i) == _status.photo_list.end() &&
×
2069
                   safety_count < safety_count_boundary) {
2070
                safety_count++;
×
2071

2072
                auto request_try_number = 0;
×
2073
                const auto request_try_limit =
×
2074
                    10; // Timeout if the request times out that many times
2075
                auto cv_status = std::cv_status::timeout;
×
2076

2077
                while (cv_status == std::cv_status::timeout) {
×
2078
                    request_try_number++;
×
2079
                    if (request_try_number >= request_try_limit) {
×
2080
                        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2081
                        _status.is_fetching_photos = false;
×
2082
                        _system_impl->call_user_callback([callback]() {
×
2083
                            callback(Camera::Result::Timeout, std::vector<Camera::CaptureInfo>{});
2084
                        });
2085
                        return;
×
2086
                    }
2087

2088
                    _system_impl->send_command_async(
×
2089
                        make_command_request_camera_image_captured(i), nullptr);
2090
                    cv_status = _captured_request_cv.wait_for(
×
2091
                        capture_request_lock, std::chrono::seconds(1));
×
2092
                }
2093
            }
2094

2095
            if (safety_count == safety_count_boundary) {
×
2096
                std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2097
                _status.is_fetching_photos = false;
×
2098
                _system_impl->call_user_callback([callback]() {
×
2099
                    callback(Camera::Result::Error, std::vector<Camera::CaptureInfo>{});
2100
                });
2101
                return;
×
2102
            }
2103
        }
2104

2105
        std::vector<Camera::CaptureInfo> photo_list;
×
2106
        {
2107
            std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2108

2109
            for (auto capture_info : _status.photo_list) {
×
2110
                if (capture_info.first >= start_index) {
×
2111
                    photo_list.push_back(capture_info.second);
×
2112
                }
2113
            }
2114

2115
            _status.is_fetching_photos = false;
×
2116

2117
            const auto temp_callback = callback;
×
2118
            _system_impl->call_user_callback([temp_callback, photo_list]() {
×
2119
                temp_callback(Camera::Result::Success, photo_list);
2120
            });
2121
        }
2122
    }).detach();
×
2123
}
2124

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

© 2026 Coveralls, Inc