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

mavlink / MAVSDK / 5126554599

pending completion
5126554599

push

github

web-flow
Merge pull request #2048 from mavlink/pr-camera-xml-fixes

Camera definition: accept bool type in xml

51 of 51 new or added lines in 4 files covered. (100.0%)

7718 of 24884 relevant lines covered (31.02%)

20.6 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(
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
    // for backwards compatibility with Yuneec drones
214
    if (_system_impl->has_autopilot()) {
×
215
        request_flight_information();
×
216

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

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

231
void CameraImpl::manual_disable()
×
232
{
233
    invalidate_params();
×
234
    _system_impl->remove_call_every(_camera_information_call_every_cookie);
×
235

236
    if (_flight_information_call_every_cookie) {
×
237
        _system_impl->remove_call_every(_flight_information_call_every_cookie);
×
238
    }
239

240
    _camera_found = false;
×
241
}
×
242

243
void CameraImpl::update_component()
×
244
{
245
    uint8_t cmp_id = _camera_id + MAV_COMP_ID_CAMERA;
×
246
    _system_impl->update_componentid_messages_handler(
×
247
        MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, cmp_id, this);
248

249
    _system_impl->update_componentid_messages_handler(
×
250
        MAVLINK_MSG_ID_STORAGE_INFORMATION, cmp_id, this);
251

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

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

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

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

263
    _system_impl->update_componentid_messages_handler(
×
264
        MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, cmp_id, this);
265
}
×
266

267
Camera::Result CameraImpl::select_camera(const size_t id)
×
268
{
269
    static constexpr std::size_t MAX_SUPPORTED_ID = 5;
270

271
    if (id > MAX_SUPPORTED_ID) {
×
272
        return Camera::Result::WrongArgument;
×
273
    }
274

275
    // camera component IDs go from 100 to 105.
276
    _camera_id = id;
×
277

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

284
    return Camera::Result::Success;
×
285
}
286

287
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_flight_information()
×
288
{
289
    MavlinkCommandSender::CommandLong command_flight_information{};
×
290

291
    command_flight_information.command = MAV_CMD_REQUEST_FLIGHT_INFORMATION;
×
292
    command_flight_information.params.maybe_param1 = 1.0f; // Request it
×
293
    command_flight_information.target_component_id = MAV_COMP_ID_AUTOPILOT1;
×
294

295
    return command_flight_information;
×
296
}
297

298
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_camera_info()
×
299
{
300
    MavlinkCommandSender::CommandLong command_camera_info{};
×
301

302
    command_camera_info.command = MAV_CMD_REQUEST_CAMERA_INFORMATION;
×
303
    command_camera_info.params.maybe_param1 = 1.0f; // Request it
×
304
    command_camera_info.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
305

306
    return command_camera_info;
×
307
}
308

309
MavlinkCommandSender::CommandLong
310
CameraImpl::make_command_take_photo(float interval_s, float no_of_photos)
×
311
{
312
    MavlinkCommandSender::CommandLong cmd_take_photo{};
×
313

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

321
    return cmd_take_photo;
×
322
}
323

324
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_photo()
×
325
{
326
    MavlinkCommandSender::CommandLong cmd_stop_photo{};
×
327

328
    cmd_stop_photo.command = MAV_CMD_IMAGE_STOP_CAPTURE;
×
329
    cmd_stop_photo.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
330

331
    return cmd_stop_photo;
×
332
}
333

334
MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video(float capture_status_rate_hz)
×
335
{
336
    MavlinkCommandSender::CommandLong cmd_start_video{};
×
337

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

343
    return cmd_start_video;
×
344
}
345

346
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video()
×
347
{
348
    MavlinkCommandSender::CommandLong cmd_stop_video{};
×
349

350
    cmd_stop_video.command = MAV_CMD_VIDEO_STOP_CAPTURE;
×
351
    cmd_stop_video.params.maybe_param1 = 0.f; // Reserved, set to 0
×
352
    cmd_stop_video.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
353

354
    return cmd_stop_video;
×
355
}
356

357
MavlinkCommandSender::CommandLong CameraImpl::make_command_set_camera_mode(float mavlink_mode)
×
358
{
359
    MavlinkCommandSender::CommandLong cmd_set_camera_mode{};
×
360

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

366
    return cmd_set_camera_mode;
×
367
}
368

369
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_camera_settings()
×
370
{
371
    MavlinkCommandSender::CommandLong cmd_req_camera_settings{};
×
372

373
    cmd_req_camera_settings.command = MAV_CMD_REQUEST_CAMERA_SETTINGS;
×
374
    cmd_req_camera_settings.params.maybe_param1 = 1.f; // Request it
×
375
    cmd_req_camera_settings.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
376

377
    return cmd_req_camera_settings;
×
378
}
379

380
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_camera_capture_status()
×
381
{
382
    MavlinkCommandSender::CommandLong cmd_req_camera_cap_stat{};
×
383

384
    cmd_req_camera_cap_stat.command = MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS;
×
385
    cmd_req_camera_cap_stat.params.maybe_param1 = 1.0f; // Request it
×
386
    cmd_req_camera_cap_stat.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
387

388
    return cmd_req_camera_cap_stat;
×
389
}
390

391
MavlinkCommandSender::CommandLong
392
CameraImpl::make_command_request_camera_image_captured(const size_t photo_id)
×
393
{
394
    MavlinkCommandSender::CommandLong cmd_req_camera_image_captured{};
×
395

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

402
    return cmd_req_camera_image_captured;
×
403
}
404

405
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_storage_info()
×
406
{
407
    MavlinkCommandSender::CommandLong cmd_req_storage_info{};
×
408

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

414
    return cmd_req_storage_info;
×
415
}
416

417
MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video_streaming()
×
418
{
419
    MavlinkCommandSender::CommandLong cmd_start_video_streaming{};
×
420

421
    cmd_start_video_streaming.command = MAV_CMD_VIDEO_START_STREAMING;
×
422
    cmd_start_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
423

424
    return cmd_start_video_streaming;
×
425
}
426

427
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video_streaming()
×
428
{
429
    MavlinkCommandSender::CommandLong cmd_stop_video_streaming{};
×
430

431
    cmd_stop_video_streaming.command = MAV_CMD_VIDEO_STOP_STREAMING;
×
432
    cmd_stop_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
433

434
    return cmd_stop_video_streaming;
×
435
}
436

437
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_video_stream_info()
×
438
{
439
    MavlinkCommandSender::CommandLong cmd_req_video_stream_info{};
×
440

441
    cmd_req_video_stream_info.command = MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION;
×
442
    cmd_req_video_stream_info.params.maybe_param2 = 1.0f;
×
443
    cmd_req_video_stream_info.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
444

445
    return cmd_req_video_stream_info;
×
446
}
447

448
MavlinkCommandSender::CommandLong CameraImpl::make_command_request_video_stream_status()
×
449
{
450
    MavlinkCommandSender::CommandLong cmd_req_video_stream_status{};
×
451

452
    cmd_req_video_stream_status.command = MAV_CMD_REQUEST_VIDEO_STREAM_STATUS;
×
453
    cmd_req_video_stream_status.params.maybe_param2 = 1.0f;
×
454
    cmd_req_video_stream_status.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
455

456
    return cmd_req_video_stream_status;
×
457
}
458

459
Camera::Result CameraImpl::take_photo()
×
460
{
461
    // TODO: check whether we are in photo mode.
462

463
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
464

465
    // Take 1 photo only with no interval
466
    auto cmd_take_photo = make_command_take_photo(0.f, 1.0f);
×
467

468
    return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo));
×
469
}
470

471
Camera::Result CameraImpl::start_photo_interval(float interval_s)
×
472
{
473
    if (!interval_valid(interval_s)) {
×
474
        return Camera::Result::WrongArgument;
×
475
    }
476

477
    // TODO: check whether we are in photo mode.
478

479
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
480

481
    auto cmd_take_photo_time_lapse = make_command_take_photo(interval_s, 0.f);
×
482

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

486
Camera::Result CameraImpl::stop_photo_interval()
×
487
{
488
    auto cmd_stop_photo_interval = make_command_stop_photo();
×
489

490
    return camera_result_from_command_result(_system_impl->send_command(cmd_stop_photo_interval));
×
491
}
492

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

498
    // Capture status rate is not set
499
    auto cmd_start_video = make_command_start_video(0.f);
×
500

501
    return camera_result_from_command_result(_system_impl->send_command(cmd_start_video));
×
502
}
503

504
Camera::Result CameraImpl::stop_video()
×
505
{
506
    auto cmd_stop_video = make_command_stop_video();
×
507

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

513
    return camera_result_from_command_result(_system_impl->send_command(cmd_stop_video));
×
514
}
515

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

520
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
521

522
    // Take 1 photo only with no interval
523
    auto cmd_take_photo = make_command_take_photo(0.f, 1.0f);
×
524

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

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

541
    // TODO: check whether we are in photo mode.
542

543
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
544

545
    auto cmd_take_photo_time_lapse = make_command_take_photo(interval_s, 0.f);
×
546

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

553
void CameraImpl::stop_photo_interval_async(const Camera::ResultCallback& callback)
×
554
{
555
    auto cmd_stop_photo_interval = make_command_stop_photo();
×
556

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

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

568
    // Capture status rate is not set
569
    auto cmd_start_video = make_command_start_video(0.f);
×
570

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

577
void CameraImpl::stop_video_async(const Camera::ResultCallback& callback)
×
578
{
579
    auto cmd_stop_video = make_command_stop_video();
×
580

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

587
Camera::Information CameraImpl::information() const
×
588
{
589
    std::lock_guard<std::mutex> lock(_information.mutex);
×
590

591
    return _information.data;
×
592
}
593

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

600
    // If there was already a subscription, cancel the call
601
    if (_status.call_every_cookie) {
×
602
        _system_impl->remove_call_every(_status.call_every_cookie);
×
603
    }
604

605
    if (callback) {
×
606
        if (_status.call_every_cookie == nullptr) {
×
607
            _system_impl->add_call_every(
×
608
                [this]() { request_status(); }, 5.0, &_status.call_every_cookie);
×
609
        }
610
    } else {
611
        _system_impl->remove_call_every(_status.call_every_cookie);
×
612
        _status.call_every_cookie = nullptr;
×
613
    }
614

615
    return handle;
×
616
}
617

618
void CameraImpl::unsubscribe_information(Camera::InformationHandle handle)
×
619
{
620
    std::lock_guard<std::mutex> lock(_information.mutex);
×
621
    _information.subscription_callbacks.unsubscribe(handle);
×
622
}
×
623

624
Camera::Result CameraImpl::start_video_streaming()
×
625
{
626
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
627

628
    if (_video_stream_info.available &&
×
629
        _video_stream_info.data.status == Camera::VideoStreamInfo::VideoStreamStatus::InProgress) {
×
630
        return Camera::Result::InProgress;
×
631
    }
632

633
    // TODO Check whether we're in video mode
634
    auto command = make_command_start_video_streaming();
×
635

636
    auto result = camera_result_from_command_result(_system_impl->send_command(command));
×
637
    // if (result == Camera::Result::Success) {
638
    // Cache video stream info; app may query immediately next.
639
    // TODO: check if we can/should do that.
640
    // auto info = get_video_stream_info();
641
    //}
642
    return result;
×
643
}
644

645
Camera::Result CameraImpl::stop_video_streaming()
×
646
{
647
    // TODO I think we need to maintain current state, whether we issued
648
    // video capture request or video streaming request, etc.We shouldn't
649
    // send stop video streaming if we've not started it!
650
    auto command = make_command_stop_video_streaming();
×
651

652
    auto result = camera_result_from_command_result(_system_impl->send_command(command));
×
653
    {
654
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
655
        // TODO: check if we can/should do that.
656
        _video_stream_info.data.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning;
×
657
    }
658
    return result;
×
659
}
660

661
void CameraImpl::request_video_stream_info()
×
662
{
663
    _system_impl->send_command_async(make_command_request_video_stream_info(), nullptr);
×
664
    _system_impl->send_command_async(make_command_request_video_stream_status(), nullptr);
×
665
}
×
666

667
Camera::VideoStreamInfo CameraImpl::video_stream_info()
×
668
{
669
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
670

671
    return _video_stream_info.data;
×
672
}
673

674
Camera::VideoStreamInfoHandle
675
CameraImpl::subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& callback)
×
676
{
677
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
678

679
    auto handle = _video_stream_info.subscription_callbacks.subscribe(callback);
×
680

681
    if (callback) {
×
682
        _system_impl->add_call_every(
×
683
            [this]() { request_video_stream_info(); }, 1.0, &_video_stream_info.call_every_cookie);
×
684
    } else {
685
        _system_impl->remove_call_every(_video_stream_info.call_every_cookie);
×
686
    }
687

688
    return handle;
×
689
}
690

691
void CameraImpl::unsubscribe_video_stream_info(Camera::VideoStreamInfoHandle handle)
×
692
{
693
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
694
    _video_stream_info.subscription_callbacks.unsubscribe(handle);
×
695
}
×
696

697
Camera::Result
698
CameraImpl::camera_result_from_command_result(const MavlinkCommandSender::Result command_result)
×
699
{
700
    switch (command_result) {
×
701
        case MavlinkCommandSender::Result::Success:
×
702
            return Camera::Result::Success;
×
703
        case MavlinkCommandSender::Result::NoSystem:
×
704
            // FALLTHROUGH
705
        case MavlinkCommandSender::Result::ConnectionError:
706
            // FALLTHROUGH
707
        case MavlinkCommandSender::Result::Busy:
708
            return Camera::Result::Error;
×
709
        case MavlinkCommandSender::Result::Denied:
×
710
            // FALLTHROUGH
711
        case MavlinkCommandSender::Result::TemporarilyRejected:
712
            return Camera::Result::Denied;
×
713
        case MavlinkCommandSender::Result::Timeout:
×
714
            return Camera::Result::Timeout;
×
715
        default:
×
716
            return Camera::Result::Unknown;
×
717
    }
718
}
719

720
Camera::Result CameraImpl::camera_result_from_parameter_result(
×
721
    const MavlinkParameterClient::Result parameter_result)
722
{
723
    switch (parameter_result) {
×
724
        case MavlinkParameterClient::Result::Success:
×
725
            return Camera::Result::Success;
×
726
        case MavlinkParameterClient::Result::Timeout:
×
727
            return Camera::Result::Timeout;
×
728
        case MavlinkParameterClient::Result::ConnectionError:
×
729
            return Camera::Result::Error;
×
730
        case MavlinkParameterClient::Result::WrongType:
×
731
            return Camera::Result::WrongArgument;
×
732
        case MavlinkParameterClient::Result::ParamNameTooLong:
×
733
            return Camera::Result::WrongArgument;
×
734
        case MavlinkParameterClient::Result::NotFound:
×
735
            return Camera::Result::WrongArgument;
×
736
        case MavlinkParameterClient::Result::ValueUnsupported:
×
737
            return Camera::Result::WrongArgument;
×
738
        case MavlinkParameterClient::Result::Failed:
×
739
            return Camera::Result::Error;
×
740
        case MavlinkParameterClient::Result::UnknownError:
×
741
            return Camera::Result::Error;
×
742
        default:
×
743
            return Camera::Result::Unknown;
×
744
    }
745
}
746

747
Camera::Result CameraImpl::set_mode(const Camera::Mode mode)
×
748
{
749
    const float mavlink_mode = to_mavlink_camera_mode(mode);
×
750
    auto cmd_set_camera_mode = make_command_set_camera_mode(mavlink_mode);
×
751
    const auto command_result = _system_impl->send_command(cmd_set_camera_mode);
×
752
    const auto camera_result = camera_result_from_command_result(command_result);
×
753

754
    if (camera_result == Camera::Result::Success) {
×
755
        {
756
            std::lock_guard<std::mutex> lock(_mode.mutex);
×
757
            _mode.data = mode;
×
758
        }
759
        notify_mode();
×
760
        if (_camera_definition != nullptr) {
×
761
            save_camera_mode(mavlink_mode);
×
762
        }
763
    }
764

765
    return camera_result;
×
766
}
767

768
void CameraImpl::save_camera_mode(const float mavlink_camera_mode)
×
769
{
770
    if (!std::isfinite(mavlink_camera_mode)) {
×
771
        LogWarn() << "Can't save NAN as camera mode";
×
772
        return;
×
773
    }
774

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

812
    _camera_definition->set_setting("CAM_MODE", value);
×
813
    refresh_params();
×
814
}
815

816
float CameraImpl::to_mavlink_camera_mode(const Camera::Mode mode) const
×
817
{
818
    switch (mode) {
×
819
        case Camera::Mode::Photo:
×
820
            return CAMERA_MODE_IMAGE;
×
821
        case Camera::Mode::Video:
×
822
            return CAMERA_MODE_VIDEO;
×
823
        default:
×
824
        case Camera::Mode::Unknown:
825
            return NAN;
×
826
    }
827
}
828

829
void CameraImpl::set_mode_async(const Camera::Mode mode, const Camera::ResultCallback& callback)
×
830
{
831
    const auto mavlink_mode = to_mavlink_camera_mode(mode);
×
832
    auto cmd_set_camera_mode = make_command_set_camera_mode(mavlink_mode);
×
833

834
    _system_impl->send_command_async(
×
835
        cmd_set_camera_mode,
836
        [this, callback, mode](MavlinkCommandSender::Result result, float progress) {
×
837
            UNUSED(progress);
×
838
            receive_set_mode_command_result(result, callback, mode);
×
839
        });
×
840
}
×
841

842
Camera::Mode CameraImpl::mode()
×
843
{
844
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
845
    return _mode.data;
×
846
}
847

848
Camera::ModeHandle CameraImpl::subscribe_mode(const Camera::ModeCallback& callback)
×
849
{
850
    std::unique_lock<std::mutex> lock(_mode.mutex);
×
851
    auto handle = _mode.subscription_callbacks.subscribe(callback);
×
852
    lock.unlock();
×
853

854
    notify_mode();
×
855

856
    if (callback) {
×
857
        _system_impl->add_call_every(
×
858
            [this]() { request_camera_settings(); }, 5.0, &_mode.call_every_cookie);
×
859
    } else {
860
        _system_impl->remove_call_every(_mode.call_every_cookie);
×
861
    }
862

863
    return handle;
×
864
}
865

866
void CameraImpl::unsubscribe_mode(Camera::ModeHandle handle)
×
867
{
868
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
869
    _mode.subscription_callbacks.unsubscribe(handle);
×
870
}
×
871

872
bool CameraImpl::interval_valid(float interval_s)
×
873
{
874
    // Reject everything faster than 1000 Hz, as well as negative inputs.
875
    if (interval_s < 0.001f) {
×
876
        LogWarn() << "Invalid interval input";
×
877
        return false;
×
878
    } else {
879
        return true;
×
880
    }
881
}
882

883
void CameraImpl::request_status()
×
884
{
885
    _system_impl->send_command_async(make_command_request_camera_capture_status(), nullptr);
×
886
    _system_impl->send_command_async(make_command_request_storage_info(), nullptr);
×
887
}
×
888

889
Camera::StatusHandle CameraImpl::subscribe_status(const Camera::StatusCallback& callback)
×
890
{
891
    std::lock_guard<std::mutex> lock(_status.mutex);
×
892

893
    auto handle = _status.subscription_callbacks.subscribe(callback);
×
894

895
    if (callback) {
×
896
        if (_status.call_every_cookie == nullptr) {
×
897
            _system_impl->add_call_every(
×
898
                [this]() { request_status(); }, 5.0, &_status.call_every_cookie);
×
899
        }
900
    } else {
901
        _system_impl->remove_call_every(_status.call_every_cookie);
×
902
        _status.call_every_cookie = nullptr;
×
903
    }
904

905
    return handle;
×
906
}
907

908
void CameraImpl::unsubscribe_status(Camera::StatusHandle handle)
×
909
{
910
    std::lock_guard<std::mutex> lock(_status.mutex);
×
911
    _status.subscription_callbacks.unsubscribe(handle);
×
912
}
×
913

914
Camera::Status CameraImpl::status()
×
915
{
916
    std::lock_guard<std::mutex> lock(_status.mutex);
×
917
    return _status.data;
×
918
}
919

920
Camera::CaptureInfoHandle
921
CameraImpl::subscribe_capture_info(const Camera::CaptureInfoCallback& callback)
×
922
{
923
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
924
    return _capture_info.callbacks.subscribe(callback);
×
925
}
926

927
void CameraImpl::unsubscribe_capture_info(Camera::CaptureInfoHandle handle)
×
928
{
929
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
930
    _capture_info.callbacks.unsubscribe(handle);
×
931
}
×
932

933
void CameraImpl::process_camera_capture_status(const mavlink_message_t& message)
×
934
{
935
    mavlink_camera_capture_status_t camera_capture_status;
×
936
    mavlink_msg_camera_capture_status_decode(&message, &camera_capture_status);
×
937

938
    // If image_count got smaller, consider that the storage was formatted.
939
    if (camera_capture_status.image_count < _status.image_count) {
×
940
        LogDebug() << "Seems like storage was formatted, setting state accordingly";
×
941
        reset_following_format_storage();
×
942
    }
943

944
    {
945
        std::lock_guard<std::mutex> lock(_status.mutex);
×
946

947
        _status.data.video_on = (camera_capture_status.video_status == 1);
×
948
        _status.data.photo_interval_on =
×
949
            (camera_capture_status.image_status == 2 || camera_capture_status.image_status == 3);
×
950
        _status.received_camera_capture_status = true;
×
951
        _status.data.recording_time_s = float(camera_capture_status.recording_time_ms) / 1e3f;
×
952

953
        _status.image_count = camera_capture_status.image_count;
×
954

955
        if (_status.image_count_at_connection == -1) {
×
956
            _status.image_count_at_connection = camera_capture_status.image_count;
×
957
        }
958
    }
959

960
    check_status();
×
961
}
×
962

963
void CameraImpl::process_storage_information(const mavlink_message_t& message)
×
964
{
965
    mavlink_storage_information_t storage_information;
×
966
    mavlink_msg_storage_information_decode(&message, &storage_information);
×
967

968
    if (storage_information.total_capacity == 0.0f) {
×
969
        // Some MAVLink systems happen to send the STORAGE_INFORMATION message
970
        // to indicate that the camera has a slot for a storage even if there
971
        // is no way to know anything about that storage (e.g. whether or not
972
        // there is an sdcard in the slot).
973
        //
974
        // We consider that a total capacity of 0 means that this is such a
975
        // message, and we don't expect MAVSDK users to leverage it, which is
976
        // why it is ignored.
977
        return;
×
978
    }
979

980
    {
981
        std::lock_guard<std::mutex> lock(_status.mutex);
×
982
        switch (storage_information.status) {
×
983
            case STORAGE_STATUS_EMPTY:
×
984
                _status.data.storage_status = Camera::Status::StorageStatus::NotAvailable;
×
985
                break;
×
986
            case STORAGE_STATUS_UNFORMATTED:
×
987
                _status.data.storage_status = Camera::Status::StorageStatus::Unformatted;
×
988
                break;
×
989
            case STORAGE_STATUS_READY:
×
990
                _status.data.storage_status = Camera::Status::StorageStatus::Formatted;
×
991
                break;
×
992
            case STORAGE_STATUS_NOT_SUPPORTED:
×
993
                _status.data.storage_status = Camera::Status::StorageStatus::NotSupported;
×
994
                break;
×
995
            default:
×
996
                _status.data.storage_status = Camera::Status::StorageStatus::NotSupported;
×
997
                LogErr() << "Unknown storage status received.";
×
998
                break;
×
999
        }
1000

1001
        _status.data.available_storage_mib = storage_information.available_capacity;
×
1002
        _status.data.used_storage_mib = storage_information.used_capacity;
×
1003
        _status.data.total_storage_mib = storage_information.total_capacity;
×
1004
        _status.data.storage_id = storage_information.storage_id;
×
1005
        _status.data.storage_type =
×
1006
            static_cast<Camera::Status::StorageType>(storage_information.type);
×
1007
        _status.received_storage_information = true;
×
1008
    }
1009

1010
    check_status();
×
1011
}
1012

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

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

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

1037
        _captured_request_cv.notify_all();
×
1038

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1230
    return true;
×
1231
}
1232

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

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

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

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

1276
    return false;
×
1277
}
1278

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

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

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

1307
    notify_video_stream_info();
×
1308
}
×
1309

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

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

1336
    notify_video_stream_info();
×
1337
}
×
1338

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1857
    return results;
1858
}
1859

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

2116
            _status.is_fetching_photos = false;
×
2117

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

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