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

mavlink / MAVSDK / 6180787766

14 Sep 2023 04:05AM UTC coverage: 31.23% (+0.02%) from 31.215%
6180787766

push

github

web-flow
Merge pull request #2141 from mavlink/fix-camera-subscription-conflict

camera: fix conflict between subscribe_status and subscribe_information

2 of 2 new or added lines in 1 file covered. (100.0%)

7821 of 25043 relevant lines covered (31.23%)

22.95 hits per line

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

4.78
/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(
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(
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(
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(
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(
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(
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(
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;
×
249
    _system_impl->update_componentid_messages_handler(
×
250
        MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, cmp_id, this);
251

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

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

258
    _system_impl->update_componentid_messages_handler(MAVLINK_MSG_ID_CAMERA_SETTINGS, cmp_id, this);
×
259

260
    _system_impl->update_componentid_messages_handler(
×
261
        MAVLINK_MSG_ID_CAMERA_INFORMATION, cmp_id, this);
262

263
    _system_impl->update_componentid_messages_handler(
×
264
        MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, cmp_id, this);
265

266
    _system_impl->update_componentid_messages_handler(
×
267
        MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, cmp_id, this);
268
}
×
269

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

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

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

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

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

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

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

298
    return command_flight_information;
×
299
}
300

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

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

309
    return command_camera_info;
×
310
}
311

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

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

324
    return cmd_take_photo;
×
325
}
326

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

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

334
    return cmd_stop_photo;
×
335
}
336

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

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

346
    return cmd_start_video;
×
347
}
348

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

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

357
    return cmd_stop_video;
×
358
}
359

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

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

369
    return cmd_set_camera_mode;
×
370
}
371

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

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

380
    return cmd_req_camera_settings;
×
381
}
382

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

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

391
    return cmd_req_camera_cap_stat;
×
392
}
393

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

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

405
    return cmd_req_camera_image_captured;
×
406
}
407

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

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

417
    return cmd_req_storage_info;
×
418
}
419

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

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

427
    return cmd_start_video_streaming;
×
428
}
429

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

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

437
    return cmd_stop_video_streaming;
×
438
}
439

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

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

448
    return cmd_req_video_stream_info;
×
449
}
450

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

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

459
    return cmd_req_video_stream_status;
×
460
}
461

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

594
    return _information.data;
×
595
}
596

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

603
    return handle;
×
604
}
605

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

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

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

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

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

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

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

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

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

659
    return _video_stream_info.data;
×
660
}
661

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

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

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

676
    return handle;
×
677
}
678

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

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

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

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

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

753
    return camera_result;
×
754
}
755

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

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

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

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

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

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

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

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

842
    notify_mode();
×
843

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

851
    return handle;
×
852
}
853

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

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

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

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

882
    return handle;
×
883
}
884

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

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

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

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

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

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

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

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

930
        _status.image_count = camera_capture_status.image_count;
×
931

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

937
    check_status();
×
938
}
×
939

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

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

957
    {
958
        std::lock_guard<std::mutex> lock(_status.mutex);
×
959
        switch (storage_information.status) {
×
960
            case STORAGE_STATUS_EMPTY:
×
961
                _status.data.storage_status = Camera::Status::StorageStatus::NotAvailable;
×
962
                break;
×
963
            case STORAGE_STATUS_UNFORMATTED:
×
964
                _status.data.storage_status = Camera::Status::StorageStatus::Unformatted;
×
965
                break;
×
966
            case STORAGE_STATUS_READY:
×
967
                _status.data.storage_status = Camera::Status::StorageStatus::Formatted;
×
968
                break;
×
969
            case STORAGE_STATUS_NOT_SUPPORTED:
×
970
                _status.data.storage_status = Camera::Status::StorageStatus::NotSupported;
×
971
                break;
×
972
            default:
×
973
                _status.data.storage_status = Camera::Status::StorageStatus::NotSupported;
×
974
                LogErr() << "Unknown storage status received.";
×
975
                break;
×
976
        }
977

978
        _status.data.available_storage_mib = storage_information.available_capacity;
×
979
        _status.data.used_storage_mib = storage_information.used_capacity;
×
980
        _status.data.total_storage_mib = storage_information.total_capacity;
×
981
        _status.data.storage_id = storage_information.storage_id;
×
982
        _status.data.storage_type =
×
983
            static_cast<Camera::Status::StorageType>(storage_information.type);
×
984
        _status.received_storage_information = true;
×
985
    }
986

987
    check_status();
×
988
}
989

990
void CameraImpl::process_camera_image_captured(const mavlink_message_t& message)
×
991
{
992
    mavlink_camera_image_captured_t image_captured;
×
993
    mavlink_msg_camera_image_captured_decode(&message, &image_captured);
×
994

995
    {
996
        Camera::CaptureInfo capture_info = {};
×
997
        capture_info.position.latitude_deg = image_captured.lat / 1e7;
×
998
        capture_info.position.longitude_deg = image_captured.lon / 1e7;
×
999
        capture_info.position.absolute_altitude_m = image_captured.alt / 1e3f;
×
1000
        capture_info.position.relative_altitude_m = image_captured.relative_alt / 1e3f;
×
1001
        capture_info.time_utc_us = image_captured.time_utc;
×
1002
        capture_info.attitude_quaternion.w = image_captured.q[0];
×
1003
        capture_info.attitude_quaternion.x = image_captured.q[1];
×
1004
        capture_info.attitude_quaternion.y = image_captured.q[2];
×
1005
        capture_info.attitude_quaternion.z = image_captured.q[3];
×
1006
        capture_info.attitude_euler_angle =
1007
            to_euler_angle_from_quaternion(capture_info.attitude_quaternion);
×
1008
        capture_info.file_url = std::string(image_captured.file_url);
×
1009
        capture_info.is_success = (image_captured.capture_result == 1);
×
1010
        capture_info.index = image_captured.image_index;
×
1011

1012
        _status.photo_list.insert(std::make_pair(image_captured.image_index, capture_info));
×
1013

1014
        _captured_request_cv.notify_all();
×
1015

1016
        std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1017
        // Notify user if a new image has been captured.
1018
        if (_capture_info.last_advertised_image_index < capture_info.index) {
×
1019
            _capture_info.callbacks.queue(
×
1020
                capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1021

1022
            if (_capture_info.last_advertised_image_index != -1) {
×
1023
                // Save captured indices that have been dropped to request later, however, don't
1024
                // do it from the very beginning as there might be many photos from a previous
1025
                // time that we don't want to request.
1026
                for (int i = _capture_info.last_advertised_image_index + 1; i < capture_info.index;
×
1027
                     ++i) {
1028
                    if (_capture_info.missing_image_retries.find(i) ==
×
1029
                        _capture_info.missing_image_retries.end()) {
×
1030
                        _capture_info.missing_image_retries[i] = 0;
×
1031
                    }
1032
                }
1033
            }
1034

1035
            _capture_info.last_advertised_image_index = capture_info.index;
×
1036
        }
1037

1038
        else if (auto it = _capture_info.missing_image_retries.find(capture_info.index);
×
1039
                 it != _capture_info.missing_image_retries.end()) {
×
1040
            _capture_info.callbacks.queue(
×
1041
                capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1042
            _capture_info.missing_image_retries.erase(it);
×
1043
        }
1044
    }
1045
}
×
1046

1047
void CameraImpl::request_missing_capture_info()
×
1048
{
1049
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1050

1051
    for (auto it = _capture_info.missing_image_retries.begin();
×
1052
         it != _capture_info.missing_image_retries.end();
×
1053
         /* ++it */) {
1054
        if (it->second > 3) {
×
1055
            it = _capture_info.missing_image_retries.erase(it);
×
1056
        } else {
1057
            ++it;
×
1058
        }
1059
    }
1060

1061
    if (!_capture_info.missing_image_retries.empty()) {
×
1062
        auto it_lowest_retries = std::min_element(
×
1063
            _capture_info.missing_image_retries.begin(), _capture_info.missing_image_retries.end());
×
1064
        _system_impl->send_command_async(
×
1065
            CameraImpl::make_command_request_camera_image_captured(it_lowest_retries->first),
×
1066
            nullptr);
1067
        it_lowest_retries->second += 1;
×
1068
    }
1069
}
×
1070

1071
Camera::EulerAngle CameraImpl::to_euler_angle_from_quaternion(Camera::Quaternion quaternion)
×
1072
{
1073
    auto& q = quaternion;
×
1074

1075
    // FIXME: This is duplicated from telemetry/math_conversions.cpp.
1076
    Camera::EulerAngle euler_angle;
×
1077
    euler_angle.roll_deg = to_deg_from_rad(
×
1078
        atan2f(2.0f * (q.w * q.x + q.y * q.z), 1.0f - 2.0f * (q.x * q.x + q.y * q.y)));
×
1079

1080
    euler_angle.pitch_deg = to_deg_from_rad(asinf(2.0f * (q.w * q.y - q.z * q.x)));
×
1081
    euler_angle.yaw_deg = to_deg_from_rad(
×
1082
        atan2f(2.0f * (q.w * q.z + q.x * q.y), 1.0f - 2.0f * (q.y * q.y + q.z * q.z)));
×
1083
    return euler_angle;
×
1084
}
1085

1086
void CameraImpl::process_camera_settings(const mavlink_message_t& message)
×
1087
{
1088
    mavlink_camera_settings_t camera_settings;
×
1089
    mavlink_msg_camera_settings_decode(&message, &camera_settings);
×
1090

1091
    {
1092
        std::lock_guard<std::mutex> lock(_mode.mutex);
×
1093
        _mode.data = to_camera_mode(camera_settings.mode_id);
×
1094
    }
1095
    notify_mode();
×
1096

1097
    if (_camera_definition) {
×
1098
        // This "parameter" needs to be manually set.
1099
        save_camera_mode(camera_settings.mode_id);
×
1100
    }
1101
}
×
1102

1103
Camera::Mode CameraImpl::to_camera_mode(const uint8_t mavlink_camera_mode) const
×
1104
{
1105
    switch (mavlink_camera_mode) {
×
1106
        case CAMERA_MODE_IMAGE:
×
1107
            return Camera::Mode::Photo;
×
1108
        case CAMERA_MODE_VIDEO:
×
1109
            return Camera::Mode::Video;
×
1110
        default:
×
1111
            return Camera::Mode::Unknown;
×
1112
    }
1113
}
1114

1115
void CameraImpl::process_camera_information(const mavlink_message_t& message)
×
1116
{
1117
    mavlink_camera_information_t camera_information;
×
1118
    mavlink_msg_camera_information_decode(&message, &camera_information);
×
1119

1120
    // Make sure all strings are zero terminated, so we don't overrun anywhere.
1121
    camera_information.vendor_name[sizeof(camera_information.vendor_name) - 1] = '\0';
×
1122
    camera_information.model_name[sizeof(camera_information.model_name) - 1] = '\0';
×
1123
    camera_information.cam_definition_uri[sizeof(camera_information.cam_definition_uri) - 1] = '\0';
×
1124

1125
    std::lock_guard<std::mutex> lock(_information.mutex);
×
1126

1127
    _information.data.vendor_name = (char*)(camera_information.vendor_name);
×
1128
    _information.data.model_name = (char*)(camera_information.model_name);
×
1129
    _information.data.focal_length_mm = camera_information.focal_length;
×
1130
    _information.data.horizontal_sensor_size_mm = camera_information.sensor_size_h;
×
1131
    _information.data.vertical_sensor_size_mm = camera_information.sensor_size_v;
×
1132
    _information.data.horizontal_resolution_px = camera_information.resolution_h;
×
1133
    _information.data.vertical_resolution_px = camera_information.resolution_v;
×
1134

1135
    _information.subscription_callbacks.queue(
×
1136
        _information.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1137

1138
    if (should_fetch_camera_definition(camera_information.cam_definition_uri)) {
×
1139
        _is_fetching_camera_definition = true;
×
1140

1141
        std::thread([this, camera_information]() {
×
1142
            std::string content{};
×
1143
            const auto has_succeeded = fetch_camera_definition(camera_information, content);
×
1144

1145
            if (has_succeeded) {
×
1146
                LogDebug() << "Successfully loaded camera definition";
×
1147

1148
                if (_camera_definition_callback) {
×
1149
                    _system_impl->call_user_callback(
×
1150
                        [this]() { _camera_definition_callback(true); });
1151
                }
1152

1153
                _camera_definition.reset(new CameraDefinition());
×
1154
                _camera_definition->load_string(content);
×
1155
                refresh_params();
×
1156
            } else {
1157
                LogDebug() << "Failed to fetch camera definition!";
×
1158

1159
                if (++_camera_definition_fetch_count >= 3) {
×
1160
                    LogWarn() << "Giving up fetching the camera definition";
×
1161

1162
                    std::lock_guard<std::mutex> thread_lock(_information.mutex);
×
1163
                    _has_camera_definition_timed_out = true;
×
1164

1165
                    if (_camera_definition_callback) {
×
1166
                        _system_impl->call_user_callback(
×
1167
                            [this]() { _camera_definition_callback(false); });
1168
                    }
1169
                }
1170
            }
1171

1172
            std::lock_guard<std::mutex> thread_lock(_information.mutex);
×
1173
            _is_fetching_camera_definition = false;
×
1174
        }).detach();
×
1175
    }
1176
}
×
1177

1178
bool CameraImpl::should_fetch_camera_definition(const std::string& uri) const
×
1179
{
1180
    return !uri.empty() && !_camera_definition && !_is_fetching_camera_definition &&
×
1181
           !_has_camera_definition_timed_out;
×
1182
}
1183

1184
bool CameraImpl::fetch_camera_definition(
×
1185
    const mavlink_camera_information_t& camera_information, std::string& camera_definition_out)
1186
{
1187
    auto download_succeeded =
1188
        download_definition_file(camera_information.cam_definition_uri, camera_definition_out);
×
1189

1190
    if (download_succeeded) {
×
1191
        return true;
×
1192
    }
1193

1194
    return load_stored_definition(camera_information, camera_definition_out);
×
1195
}
1196

1197
bool CameraImpl::download_definition_file(
×
1198
    const std::string& uri, std::string& camera_definition_out)
1199
{
1200
    HttpLoader http_loader;
×
1201
    LogInfo() << "Downloading camera definition from: " << uri;
×
1202
    if (!http_loader.download_text_sync(uri, camera_definition_out)) {
×
1203
        LogErr() << "Failed to download camera definition.";
×
1204
        return false;
×
1205
    }
1206

1207
    return true;
×
1208
}
1209

1210
bool CameraImpl::load_stored_definition(
×
1211
    const mavlink_camera_information_t& camera_information, std::string& camera_definition_out)
1212
{
1213
    // TODO: we might also try to support the correct version of the xml files.
1214

1215
    const auto vendor_name = std::string(
×
1216
        reinterpret_cast<const char*>(std::begin(camera_information.vendor_name)),
×
1217
        reinterpret_cast<const char*>(std::end(camera_information.vendor_name)));
×
1218

1219
    const auto model_name = std::string(
×
1220
        reinterpret_cast<const char*>(std::begin(camera_information.model_name)),
×
1221
        reinterpret_cast<const char*>(std::end(camera_information.model_name)));
×
1222

1223
    if (vendor_name == "Yuneec") {
×
1224
        if (model_name == "E90") {
×
1225
            LogInfo() << "Using cached file for Yuneec E90.";
×
1226
            camera_definition_out = e90xml;
×
1227
            return true;
×
1228
        } else if (model_name == "E50") {
×
1229
            LogInfo() << "Using cached file for Yuneec E50.";
×
1230
            camera_definition_out = e50xml;
×
1231
            return true;
×
1232
        } else if (model_name == "CGOET") {
×
1233
            LogInfo() << "Using cached file for Yuneec ET.";
×
1234
            camera_definition_out = cgoetxml;
×
1235
            return true;
×
1236
        } else if (model_name == "E10T") {
×
1237
            LogInfo() << "Using cached file for Yuneec E10T.";
×
1238
            camera_definition_out = e10txml;
×
1239
            return true;
×
1240
        } else if (model_name == "E30Z") {
×
1241
            LogInfo() << "Using cached file for Yuneec E30Z.";
×
1242
            camera_definition_out = e30zxml;
×
1243
            return true;
×
1244
        }
1245
    } else if (vendor_name == "Sony") {
×
1246
        if (model_name == "ILCE-7RM4") {
×
1247
            LogInfo() << "Using cached file for Sony ILCE-7RM4.";
×
1248
            camera_definition_out = ILCE7RM4xml;
×
1249
            return true;
×
1250
        }
1251
    }
1252

1253
    return false;
×
1254
}
1255

1256
void CameraImpl::process_video_information(const mavlink_message_t& message)
×
1257
{
1258
    mavlink_video_stream_information_t received_video_info;
×
1259
    mavlink_msg_video_stream_information_decode(&message, &received_video_info);
×
1260

1261
    {
1262
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1263
        // TODO: use stream_id and count
1264
        _video_stream_info.data.status =
×
1265
            (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
×
1266
                 Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1267
                 Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1268
        _video_stream_info.data.spectrum =
×
1269
            (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
×
1270
                 Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1271
                 Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1272

1273
        auto& video_stream_info = _video_stream_info.data.settings;
×
1274
        video_stream_info.frame_rate_hz = received_video_info.framerate;
×
1275
        video_stream_info.horizontal_resolution_pix = received_video_info.resolution_h;
×
1276
        video_stream_info.vertical_resolution_pix = received_video_info.resolution_v;
×
1277
        video_stream_info.bit_rate_b_s = received_video_info.bitrate;
×
1278
        video_stream_info.rotation_deg = received_video_info.rotation;
×
1279
        video_stream_info.horizontal_fov_deg = static_cast<float>(received_video_info.hfov);
×
1280
        video_stream_info.uri = received_video_info.uri;
×
1281
        _video_stream_info.available = true;
×
1282
    }
1283

1284
    notify_video_stream_info();
×
1285
}
×
1286

1287
void CameraImpl::process_video_stream_status(const mavlink_message_t& message)
×
1288
{
1289
    mavlink_video_stream_status_t received_video_stream_status;
×
1290
    mavlink_msg_video_stream_status_decode(&message, &received_video_stream_status);
×
1291
    {
1292
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1293
        _video_stream_info.data.status =
×
1294
            (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
×
1295
                 Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1296
                 Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1297
        _video_stream_info.data.spectrum =
×
1298
            (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
×
1299
                 Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1300
                 Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1301

1302
        auto& video_stream_info = _video_stream_info.data.settings;
×
1303
        video_stream_info.frame_rate_hz = received_video_stream_status.framerate;
×
1304
        video_stream_info.horizontal_resolution_pix = received_video_stream_status.resolution_h;
×
1305
        video_stream_info.vertical_resolution_pix = received_video_stream_status.resolution_v;
×
1306
        video_stream_info.bit_rate_b_s = received_video_stream_status.bitrate;
×
1307
        video_stream_info.rotation_deg = received_video_stream_status.rotation;
×
1308
        video_stream_info.horizontal_fov_deg =
×
1309
            static_cast<float>(received_video_stream_status.hfov);
×
1310
        _video_stream_info.available = true;
×
1311
    }
1312

1313
    notify_video_stream_info();
×
1314
}
×
1315

1316
void CameraImpl::process_flight_information(const mavlink_message_t& message)
×
1317
{
1318
    mavlink_flight_information_t flight_information;
×
1319
    mavlink_msg_flight_information_decode(&message, &flight_information);
×
1320

1321
    std::stringstream folder_name_stream;
×
1322
    {
1323
        std::lock_guard<std::mutex> information_lock(_information.mutex);
×
1324

1325
        // For Yuneec cameras, the folder names can be derived from the flight ID,
1326
        // starting at 100 up to 999.
1327
        if (_information.data.vendor_name == "Yuneec" && _information.data.model_name == "E90") {
×
1328
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "E90HD";
×
1329
        } else if (
×
1330
            _information.data.vendor_name == "Yuneec" && _information.data.model_name == "E50") {
×
1331
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "E50HD";
×
1332
        } else if (
×
1333
            _information.data.vendor_name == "Yuneec" && _information.data.model_name == "CGOET") {
×
1334
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "CGOET";
×
1335
        } else if (
×
1336
            _information.data.vendor_name == "Yuneec" && _information.data.model_name == "E10T") {
×
1337
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "E10T";
×
1338
        } else {
1339
            // Folder name unknown
1340
        }
1341
    }
1342

1343
    {
1344
        std::lock_guard<std::mutex> lock(_status.mutex);
×
1345
        _status.data.media_folder_name = folder_name_stream.str();
×
1346
    }
1347
}
×
1348

1349
void CameraImpl::notify_video_stream_info()
×
1350
{
1351
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1352

1353
    _video_stream_info.subscription_callbacks.queue(
×
1354
        _video_stream_info.data,
×
1355
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1356
}
×
1357

1358
void CameraImpl::check_status()
×
1359
{
1360
    std::lock_guard<std::mutex> lock(_status.mutex);
×
1361

1362
    if (_status.received_camera_capture_status && _status.received_storage_information) {
×
1363
        _status.subscription_callbacks.queue(
×
1364
            _status.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1365

1366
        _status.received_camera_capture_status = false;
×
1367
        _status.received_storage_information = false;
×
1368
    }
1369
}
×
1370

1371
void CameraImpl::receive_command_result(
×
1372
    MavlinkCommandSender::Result command_result, const Camera::ResultCallback& callback)
1373
{
1374
    Camera::Result camera_result = camera_result_from_command_result(command_result);
×
1375

1376
    if (callback) {
×
1377
        _system_impl->call_user_callback([callback, camera_result]() { callback(camera_result); });
×
1378
    }
1379
}
×
1380

1381
void CameraImpl::receive_set_mode_command_result(
×
1382
    const MavlinkCommandSender::Result command_result,
1383
    const Camera::ResultCallback callback,
1384
    const Camera::Mode mode)
1385
{
1386
    Camera::Result camera_result = camera_result_from_command_result(command_result);
×
1387

1388
    if (callback) {
×
1389
        const auto temp_callback = callback;
×
1390
        _system_impl->call_user_callback(
×
1391
            [temp_callback, camera_result]() { temp_callback(camera_result); });
1392
    }
1393

1394
    if (command_result == MavlinkCommandSender::Result::Success && _camera_definition) {
×
1395
        // This "parameter" needs to be manually set.
1396
        {
1397
            std::lock_guard<std::mutex> lock(_mode.mutex);
×
1398
            _mode.data = mode;
×
1399
        }
1400

1401
        const auto mavlink_mode = to_mavlink_camera_mode(mode);
×
1402

1403
        if (std::isnan(mavlink_mode)) {
×
1404
            LogWarn() << "Unknown camera mode";
×
1405
            return;
×
1406
        }
1407

1408
        notify_mode();
×
1409
        save_camera_mode(mavlink_mode);
×
1410
    }
1411
}
1412

1413
void CameraImpl::notify_mode()
×
1414
{
1415
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
1416

1417
    _mode.subscription_callbacks.queue(
×
1418
        _mode.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1419
}
×
1420

1421
bool CameraImpl::get_possible_setting_options(std::vector<std::string>& settings)
×
1422
{
1423
    settings.clear();
×
1424

1425
    if (!_camera_definition) {
×
1426
        LogWarn() << "Error: no camera definition available yet";
×
1427
        return false;
×
1428
    }
1429

1430
    std::unordered_map<std::string, ParamValue> cd_settings{};
×
1431
    _camera_definition->get_possible_settings(cd_settings);
×
1432

1433
    for (const auto& cd_setting : cd_settings) {
×
1434
        if (cd_setting.first == "CAM_MODE") {
×
1435
            // We ignore the mode param.
1436
            continue;
×
1437
        }
1438

1439
        settings.push_back(cd_setting.first);
×
1440
    }
1441

1442
    return settings.size() > 0;
×
1443
}
1444

1445
bool CameraImpl::get_possible_options(
×
1446
    const std::string& setting_id, std::vector<Camera::Option>& options)
1447
{
1448
    options.clear();
×
1449

1450
    if (!_camera_definition) {
×
1451
        LogWarn() << "Error: no camera definition available yet";
×
1452
        return false;
×
1453
    }
1454

1455
    std::vector<ParamValue> values;
×
1456
    if (!_camera_definition->get_possible_options(setting_id, values)) {
×
1457
        return false;
×
1458
    }
1459

1460
    for (const auto& value : values) {
×
1461
        std::stringstream ss{};
×
1462
        ss << value;
×
1463
        Camera::Option option{};
×
1464
        option.option_id = ss.str();
×
1465
        if (!is_setting_range(setting_id)) {
×
1466
            get_option_str(setting_id, option.option_id, option.option_description);
×
1467
        }
1468
        options.push_back(option);
×
1469
    }
1470

1471
    return options.size() > 0;
×
1472
}
1473

1474
bool CameraImpl::is_setting_range(const std::string& setting_id)
×
1475
{
1476
    return _camera_definition->is_setting_range(setting_id);
×
1477
}
1478

1479
Camera::Result CameraImpl::set_setting(Camera::Setting setting)
×
1480
{
1481
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1482
    auto ret = prom->get_future();
×
1483

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

1486
    return ret.get();
×
1487
}
1488

1489
void CameraImpl::set_setting_async(Camera::Setting setting, const Camera::ResultCallback callback)
×
1490
{
1491
    set_option_async(setting.setting_id, setting.option, callback);
×
1492
}
×
1493

1494
void CameraImpl::set_option_async(
×
1495
    const std::string& setting_id,
1496
    const Camera::Option& option,
1497
    const Camera::ResultCallback& callback)
1498
{
1499
    if (!_camera_definition) {
×
1500
        LogWarn() << "Error: no camera defnition available yet.";
×
1501
        if (callback) {
×
1502
            const auto temp_callback = callback;
×
1503
            _system_impl->call_user_callback(
×
1504
                [temp_callback]() { temp_callback(Camera::Result::Error); });
1505
        }
1506
        return;
×
1507
    }
1508

1509
    // We get it first so that we have the type of the param value.
1510
    ParamValue value;
×
1511

1512
    if (_camera_definition->is_setting_range(setting_id)) {
×
1513
        // TODO: Get type from minimum.
1514
        std::vector<ParamValue> all_values;
×
1515
        if (!_camera_definition->get_all_options(setting_id, all_values)) {
×
1516
            if (callback) {
×
1517
                LogErr() << "Could not get all options to get type for range param.";
×
1518
                const auto temp_callback = callback;
×
1519
                _system_impl->call_user_callback(
×
1520
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1521
            }
1522
            return;
×
1523
        }
1524

1525
        if (all_values.size() == 0) {
×
1526
            if (callback) {
×
1527
                LogErr() << "Could not get any options to get type for range param.";
×
1528
                const auto temp_callback = callback;
×
1529
                _system_impl->call_user_callback(
×
1530
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1531
            }
1532
            return;
×
1533
        }
1534
        value = all_values[0];
×
1535
        // Now re-use that type.
1536
        // FIXME: this is quite ugly, we should do better than that.
1537
        if (!value.set_as_same_type(option.option_id)) {
×
1538
            if (callback) {
×
1539
                LogErr() << "Could not set option value to given type.";
×
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
    } else {
1548
        if (!_camera_definition->get_option_value(setting_id, option.option_id, value)) {
×
1549
            if (callback) {
×
1550
                LogErr() << "Could not get option value.";
×
1551
                const auto temp_callback = callback;
×
1552
                _system_impl->call_user_callback(
×
1553
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1554
            }
1555
            return;
×
1556
        }
1557

1558
        std::vector<ParamValue> possible_values;
×
1559
        _camera_definition->get_possible_options(setting_id, possible_values);
×
1560
        bool allowed = false;
×
1561
        for (const auto& possible_value : possible_values) {
×
1562
            if (value == possible_value) {
×
1563
                allowed = true;
×
1564
            }
1565
        }
1566
        if (!allowed) {
×
1567
            LogErr() << "Setting " << setting_id << "(" << option.option_id << ") not allowed";
×
1568
            if (callback) {
×
1569
                const auto temp_callback = callback;
×
1570
                _system_impl->call_user_callback(
×
1571
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1572
            }
1573
            return;
×
1574
        }
1575
    }
1576

1577
    _system_impl->set_param_async(
×
1578
        setting_id,
1579
        value,
1580
        [this, callback, setting_id, value](MavlinkParameterClient::Result result) {
×
1581
            if (result == MavlinkParameterClient::Result::Success) {
×
1582
                if (!this->_camera_definition) {
×
1583
                    if (callback) {
×
1584
                        const auto temp_callback = callback;
×
1585
                        _system_impl->call_user_callback(
×
1586
                            [temp_callback]() { temp_callback(Camera::Result::Error); });
1587
                    }
1588
                    return;
×
1589
                }
1590

1591
                if (!_camera_definition->set_setting(setting_id, value)) {
×
1592
                    if (callback) {
×
1593
                        const auto temp_callback = callback;
×
1594
                        _system_impl->call_user_callback(
×
1595
                            [temp_callback]() { temp_callback(Camera::Result::Error); });
1596
                    }
1597
                    return;
×
1598
                }
1599

1600
                if (callback) {
×
1601
                    const auto temp_callback = callback;
×
1602
                    _system_impl->call_user_callback(
×
1603
                        [temp_callback]() { temp_callback(Camera::Result::Success); });
1604
                }
1605

1606
                // FIXME: We are already holding the lock when this lambda is run and need to
1607
                //        schedule the refresh_params() for later.
1608
                //        We (ab)use the thread pool for the user callbacks for this.
1609
                _system_impl->call_user_callback([this]() { refresh_params(); });
×
1610
            } else {
1611
                if (callback) {
×
1612
                    const auto temp_callback = callback;
×
1613
                    _system_impl->call_user_callback([temp_callback, result]() {
×
1614
                        temp_callback(camera_result_from_parameter_result(result));
1615
                    });
1616
                }
1617
            }
1618
        },
1619
        this,
1620
        static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA),
×
1621
        true);
1622
}
1623

1624
void CameraImpl::get_setting_async(
×
1625
    Camera::Setting setting, const Camera::GetSettingCallback callback)
1626
{
1627
    get_option_async(
×
1628
        setting.setting_id,
×
1629
        [this, setting, callback](Camera::Result result, const Camera::Option& option) {
×
1630
            Camera::Setting new_setting{};
×
1631
            new_setting.option = option;
×
1632
            if (callback) {
×
1633
                const auto temp_callback = callback;
×
1634
                _system_impl->call_user_callback(
×
1635
                    [temp_callback, result, new_setting]() { temp_callback(result, new_setting); });
1636
            }
1637
        });
×
1638
}
×
1639

1640
std::pair<Camera::Result, Camera::Setting> CameraImpl::get_setting(Camera::Setting setting)
×
1641
{
1642
    auto prom = std::make_shared<std::promise<std::pair<Camera::Result, Camera::Setting>>>();
×
1643
    auto ret = prom->get_future();
×
1644

1645
    get_setting_async(setting, [&prom](Camera::Result result, const Camera::Setting& new_setting) {
×
1646
        prom->set_value(std::make_pair<>(result, new_setting));
×
1647
    });
×
1648

1649
    return ret.get();
×
1650
}
1651

1652
Camera::Result CameraImpl::get_option(const std::string& setting_id, Camera::Option& option)
×
1653
{
1654
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1655
    auto ret = prom->get_future();
×
1656

1657
    get_option_async(
×
1658
        setting_id, [prom, &option](Camera::Result result, const Camera::Option& option_gotten) {
×
1659
            prom->set_value(result);
×
1660
            if (result == Camera::Result::Success) {
×
1661
                option = option_gotten;
×
1662
            }
1663
        });
×
1664

1665
    auto status = ret.wait_for(std::chrono::seconds(1));
×
1666

1667
    if (status == std::future_status::ready) {
×
1668
        return Camera::Result::Success;
×
1669
    } else {
1670
        return Camera::Result::Timeout;
×
1671
    }
1672
}
1673

1674
void CameraImpl::get_option_async(
×
1675
    const std::string& setting_id,
1676
    const std::function<void(Camera::Result, const Camera::Option&)>& callback)
1677
{
1678
    if (!_camera_definition) {
×
1679
        LogWarn() << "Error: no camera defnition available yet.";
×
1680
        if (callback) {
×
1681
            Camera::Option empty_option{};
×
1682
            const auto temp_callback = callback;
×
1683
            _system_impl->call_user_callback([temp_callback, empty_option]() {
×
1684
                temp_callback(Camera::Result::Error, empty_option);
1685
            });
1686
        }
1687
        return;
×
1688
    }
1689

1690
    ParamValue value;
×
1691
    // We should have this cached and don't need to get the param.
1692
    if (_camera_definition->get_setting(setting_id, value)) {
×
1693
        if (callback) {
×
1694
            Camera::Option new_option{};
×
1695
            new_option.option_id = value.get_string();
×
1696
            if (!is_setting_range(setting_id)) {
×
1697
                get_option_str(setting_id, new_option.option_id, new_option.option_description);
×
1698
            }
1699
            const auto temp_callback = callback;
×
1700
            _system_impl->call_user_callback([temp_callback, new_option]() {
×
1701
                temp_callback(Camera::Result::Success, new_option);
1702
            });
1703
        }
1704
    } else {
1705
        // If this still happens, we request the param, but also complain.
1706
        LogWarn() << "Setting '" << setting_id << "' not found.";
×
1707
        if (callback) {
×
1708
            Camera::Option no_option{};
×
1709
            const auto temp_callback = callback;
×
1710
            _system_impl->call_user_callback(
×
1711
                [temp_callback, no_option]() { temp_callback(Camera::Result::Error, no_option); });
1712
        }
1713
    }
1714
}
1715

1716
Camera::CurrentSettingsHandle
1717
CameraImpl::subscribe_current_settings(const Camera::CurrentSettingsCallback& callback)
×
1718
{
1719
    std::unique_lock<std::mutex> lock(_subscribe_current_settings.mutex);
×
1720
    auto handle = _subscribe_current_settings.callbacks.subscribe(callback);
×
1721
    lock.unlock();
×
1722

1723
    notify_current_settings();
×
1724
    return handle;
×
1725
}
1726

1727
void CameraImpl::unsubscribe_current_settings(Camera::CurrentSettingsHandle handle)
×
1728
{
1729
    std::lock_guard<std::mutex> lock(_subscribe_current_settings.mutex);
×
1730
    _subscribe_current_settings.callbacks.unsubscribe(handle);
×
1731
}
×
1732

1733
Camera::PossibleSettingOptionsHandle CameraImpl::subscribe_possible_setting_options(
×
1734
    const Camera::PossibleSettingOptionsCallback& callback)
1735
{
1736
    std::unique_lock<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
1737
    auto handle = _subscribe_possible_setting_options.callbacks.subscribe(callback);
×
1738
    lock.unlock();
×
1739

1740
    notify_possible_setting_options();
×
1741
    return handle;
×
1742
}
1743

1744
void CameraImpl::unsubscribe_possible_setting_options(Camera::PossibleSettingOptionsHandle handle)
×
1745
{
1746
    std::lock_guard<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
1747
    _subscribe_possible_setting_options.callbacks.unsubscribe(handle);
×
1748
}
×
1749

1750
void CameraImpl::notify_current_settings()
×
1751
{
1752
    std::lock_guard<std::mutex> lock(_subscribe_current_settings.mutex);
×
1753

1754
    if (_subscribe_current_settings.callbacks.empty()) {
×
1755
        return;
×
1756
    }
1757

1758
    if (!_camera_definition) {
×
1759
        LogErr() << "notify_current_settings has no camera definition";
×
1760
        return;
×
1761
    }
1762

1763
    std::vector<Camera::Setting> current_settings{};
×
1764
    std::vector<std::string> possible_setting_options{};
×
1765
    if (!get_possible_setting_options(possible_setting_options)) {
×
1766
        LogErr() << "Could not get possible settings in current options subscription.";
×
1767
        return;
×
1768
    }
1769

1770
    for (auto& possible_setting : possible_setting_options) {
×
1771
        // use the cache for this, presumably we updated it right before.
1772
        ParamValue value;
×
1773
        if (_camera_definition->get_setting(possible_setting, value)) {
×
1774
            Camera::Setting setting{};
×
1775
            setting.setting_id = possible_setting;
×
1776
            setting.is_range = is_setting_range(possible_setting);
×
1777
            get_setting_str(setting.setting_id, setting.setting_description);
×
1778
            setting.option.option_id = value.get_string();
×
1779
            if (!is_setting_range(possible_setting)) {
×
1780
                get_option_str(
×
1781
                    setting.setting_id,
1782
                    setting.option.option_id,
1783
                    setting.option.option_description);
1784
            }
1785
            current_settings.push_back(setting);
×
1786
        }
1787
    }
1788

1789
    _subscribe_current_settings.callbacks.queue(
×
1790
        current_settings, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1791
}
1792

1793
void CameraImpl::notify_possible_setting_options()
×
1794
{
1795
    std::lock_guard<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
1796

1797
    if (_subscribe_possible_setting_options.callbacks.empty()) {
×
1798
        return;
×
1799
    }
1800

1801
    if (!_camera_definition) {
×
1802
        LogErr() << "notify_possible_setting_options has no camera definition";
×
1803
        return;
×
1804
    }
1805

1806
    auto setting_options = possible_setting_options();
×
1807
    if (setting_options.size() == 0) {
×
1808
        return;
×
1809
    }
1810

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

1815
std::vector<Camera::SettingOptions> CameraImpl::possible_setting_options()
×
1816
{
1817
    std::vector<Camera::SettingOptions> results{};
×
1818

1819
    std::vector<std::string> possible_settings{};
×
1820
    if (!get_possible_setting_options(possible_settings)) {
×
1821
        LogErr() << "Could not get possible settings.";
×
1822
        return results;
×
1823
    }
1824

1825
    for (auto& possible_setting : possible_settings) {
×
1826
        Camera::SettingOptions setting_options{};
×
1827
        setting_options.setting_id = possible_setting;
×
1828
        setting_options.is_range = _camera_definition->is_setting_range(possible_setting);
×
1829
        get_setting_str(setting_options.setting_id, setting_options.setting_description);
×
1830
        get_possible_options(possible_setting, setting_options.options);
×
1831
        results.push_back(setting_options);
×
1832
    }
1833

1834
    return results;
1835
}
1836

1837
void CameraImpl::refresh_params()
×
1838
{
1839
    if (!_camera_definition) {
×
1840
        return;
×
1841
    }
1842

1843
    std::vector<std::pair<std::string, ParamValue>> params;
×
1844
    _camera_definition->get_unknown_params(params);
×
1845
    if (params.size() == 0) {
×
1846
        // We're assuming that we changed one option and this did not cause
1847
        // any other possible settings to change. However, we still would
1848
        // like to notify the current settings with this one change.
1849
        notify_current_settings();
×
1850
        notify_possible_setting_options();
×
1851
        return;
×
1852
    }
1853

1854
    unsigned count = 0;
×
1855
    for (const auto& param : params) {
×
1856
        const std::string& param_name = param.first;
×
1857
        const ParamValue& param_value_type = param.second;
×
1858
        const bool is_last = (count == params.size() - 1);
×
1859
        _system_impl->get_param_async(
×
1860
            param_name,
1861
            param_value_type,
1862
            [param_name, is_last, this](MavlinkParameterClient::Result result, ParamValue value) {
×
1863
                if (result != MavlinkParameterClient::Result::Success) {
×
1864
                    return;
×
1865
                }
1866
                // We need to check again by the time this callback runs
1867
                if (!this->_camera_definition) {
×
1868
                    return;
×
1869
                }
1870

1871
                if (!this->_camera_definition->set_setting(param_name, value)) {
×
1872
                    return;
×
1873
                }
1874

1875
                if (is_last) {
×
1876
                    notify_current_settings();
×
1877
                    notify_possible_setting_options();
×
1878
                }
1879
            },
1880
            this,
1881
            static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA),
×
1882
            true);
1883
        ++count;
×
1884
    }
1885
}
1886

1887
void CameraImpl::invalidate_params()
×
1888
{
1889
    if (!_camera_definition) {
×
1890
        return;
×
1891
    }
1892

1893
    _camera_definition->set_all_params_unknown();
×
1894
}
1895

1896
bool CameraImpl::get_setting_str(const std::string& setting_id, std::string& description)
×
1897
{
1898
    if (!_camera_definition) {
×
1899
        return false;
×
1900
    }
1901

1902
    return _camera_definition->get_setting_str(setting_id, description);
×
1903
}
1904

1905
bool CameraImpl::get_option_str(
×
1906
    const std::string& setting_id, const std::string& option_id, std::string& description)
1907
{
1908
    if (!_camera_definition) {
×
1909
        return false;
×
1910
    }
1911

1912
    return _camera_definition->get_option_str(setting_id, option_id, description);
×
1913
}
1914

1915
void CameraImpl::request_camera_settings()
×
1916
{
1917
    auto command_camera_settings = make_command_request_camera_settings();
×
1918
    _system_impl->send_command_async(command_camera_settings, nullptr);
×
1919
}
×
1920

1921
void CameraImpl::request_flight_information()
×
1922
{
1923
    auto command_flight_information = make_command_request_flight_information();
×
1924
    _system_impl->send_command_async(command_flight_information, nullptr);
×
1925
}
×
1926

1927
void CameraImpl::request_camera_information()
×
1928
{
1929
    auto command_camera_info = make_command_request_camera_info();
×
1930
    _system_impl->send_command_async(command_camera_info, nullptr);
×
1931
}
×
1932

1933
Camera::Result CameraImpl::format_storage()
×
1934
{
1935
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1936
    auto ret = prom->get_future();
×
1937

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

1940
    return ret.get();
×
1941
}
1942

1943
void CameraImpl::format_storage_async(Camera::ResultCallback callback)
×
1944
{
1945
    MavlinkCommandSender::CommandLong cmd_format{};
×
1946

1947
    cmd_format.command = MAV_CMD_STORAGE_FORMAT;
×
1948
    cmd_format.params.maybe_param1 = 1.0f; // storage ID
×
1949
    cmd_format.params.maybe_param2 = 1.0f; // format
×
1950
    cmd_format.params.maybe_param3 = 1.0f; // clear
×
1951
    cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
1952

1953
    _system_impl->send_command_async(
×
1954
        cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
×
1955
            UNUSED(progress);
×
1956

1957
            receive_command_result(result, [this, callback](Camera::Result camera_result) {
×
1958
                if (camera_result == Camera::Result::Success) {
×
1959
                    reset_following_format_storage();
×
1960
                }
1961

1962
                callback(camera_result);
×
1963
            });
×
1964
        });
×
1965
}
×
1966

1967
void CameraImpl::reset_following_format_storage()
×
1968
{
1969
    {
1970
        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
1971
        _status.photo_list.clear();
×
1972
        _status.image_count = 0;
×
1973
        _status.image_count_at_connection = 0;
×
1974
    }
1975
    {
1976
        std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1977
        _capture_info.last_advertised_image_index = -1;
×
1978
        _capture_info.missing_image_retries.clear();
×
1979
    }
1980
}
×
1981

1982
std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>
1983
CameraImpl::list_photos(Camera::PhotosRange photos_range)
×
1984
{
1985
    std::promise<std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>> prom;
×
1986
    auto ret = prom.get_future();
×
1987

1988
    list_photos_async(
×
1989
        photos_range, [&prom](Camera::Result result, std::vector<Camera::CaptureInfo> photo_list) {
×
1990
            prom.set_value(std::make_pair(result, photo_list));
×
1991
        });
×
1992

1993
    return ret.get();
×
1994
}
1995

1996
void CameraImpl::list_photos_async(
×
1997
    Camera::PhotosRange photos_range, const Camera::ListPhotosCallback callback)
1998
{
1999
    if (!callback) {
×
2000
        LogWarn() << "Trying to get a photo list with a null callback, ignoring...";
×
2001
        return;
×
2002
    }
2003

2004
    {
2005
        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2006

2007
        if (_status.is_fetching_photos) {
×
2008
            _system_impl->call_user_callback([callback]() {
×
2009
                callback(Camera::Result::Busy, std::vector<Camera::CaptureInfo>{});
2010
            });
2011
            return;
×
2012
        } else {
2013
            _status.is_fetching_photos = true;
×
2014
        }
2015

2016
        if (_status.image_count == -1) {
×
2017
            LogErr() << "Cannot list photos: camera status has not been received yet!";
×
2018
            _status.is_fetching_photos = false;
×
2019
            _system_impl->call_user_callback([callback]() {
×
2020
                callback(Camera::Result::Error, std::vector<Camera::CaptureInfo>{});
2021
            });
2022
            return;
×
2023
        }
2024
    }
2025

2026
    const int start_index = [this, photos_range]() {
×
2027
        switch (photos_range) {
×
2028
            case Camera::PhotosRange::SinceConnection:
×
2029
                return _status.image_count_at_connection;
×
2030
            case Camera::PhotosRange::All:
×
2031
            // FALLTHROUGH
2032
            default:
2033
                return 0;
×
2034
        }
2035
    }();
×
2036

2037
    std::thread([this, start_index, callback]() {
×
2038
        std::unique_lock<std::mutex> capture_request_lock(_captured_request_mutex);
×
2039

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

2046
            while (_status.photo_list.find(i) == _status.photo_list.end() &&
×
2047
                   safety_count < safety_count_boundary) {
2048
                safety_count++;
×
2049

2050
                auto request_try_number = 0;
×
2051
                const auto request_try_limit =
×
2052
                    10; // Timeout if the request times out that many times
2053
                auto cv_status = std::cv_status::timeout;
×
2054

2055
                while (cv_status == std::cv_status::timeout) {
×
2056
                    request_try_number++;
×
2057
                    if (request_try_number >= request_try_limit) {
×
2058
                        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2059
                        _status.is_fetching_photos = false;
×
2060
                        _system_impl->call_user_callback([callback]() {
×
2061
                            callback(Camera::Result::Timeout, std::vector<Camera::CaptureInfo>{});
2062
                        });
2063
                        return;
×
2064
                    }
2065

2066
                    _system_impl->send_command_async(
×
2067
                        make_command_request_camera_image_captured(i), nullptr);
2068
                    cv_status = _captured_request_cv.wait_for(
×
2069
                        capture_request_lock, std::chrono::seconds(1));
×
2070
                }
2071
            }
2072

2073
            if (safety_count == safety_count_boundary) {
×
2074
                std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2075
                _status.is_fetching_photos = false;
×
2076
                _system_impl->call_user_callback([callback]() {
×
2077
                    callback(Camera::Result::Error, std::vector<Camera::CaptureInfo>{});
2078
                });
2079
                return;
×
2080
            }
2081
        }
2082

2083
        std::vector<Camera::CaptureInfo> photo_list;
×
2084
        {
2085
            std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2086

2087
            for (auto capture_info : _status.photo_list) {
×
2088
                if (capture_info.first >= start_index) {
×
2089
                    photo_list.push_back(capture_info.second);
×
2090
                }
2091
            }
2092

2093
            _status.is_fetching_photos = false;
×
2094

2095
            const auto temp_callback = callback;
×
2096
            _system_impl->call_user_callback([temp_callback, photo_list]() {
×
2097
                temp_callback(Camera::Result::Success, photo_list);
2098
            });
2099
        }
2100
    }).detach();
×
2101
}
2102

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