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

mavlink / MAVSDK / 7317183253

24 Dec 2023 10:25PM UTC coverage: 36.26% (-0.6%) from 36.89%
7317183253

push

github

web-flow
Merge pull request #2088 from tbago/add_more_camera_function

More camera server functionality

28 of 718 new or added lines in 12 files covered. (3.9%)

20 existing lines in 6 files now uncovered.

10035 of 27675 relevant lines covered (36.26%)

127.93 hits per line

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

4.75
/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 "unused.h"
7
#include "callback_list.tpp"
8

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

13
namespace mavsdk {
14

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

161
    if (_camera_definition) {
×
162
        _system_impl->call_user_callback(
×
163
            [temp_callback]() { temp_callback(Camera::Result::Success); });
164
    } else {
165
        _camera_definition_callback = [this, temp_callback](Camera::Result result) {
×
166
            temp_callback(result);
×
167
            _camera_definition_callback = nullptr;
×
168
        };
×
169

170
        if (_has_camera_definition_timed_out) {
×
171
            // Try to download the camera_definition again
172
            _has_camera_definition_timed_out = false;
×
173
            request_camera_information();
×
174
        }
175
    }
176
}
×
177

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

191
void CameraImpl::enable()
1✔
192
{
193
    // FIXME: We check for the connection status manually because
194
    // we're not interested in the connection state of the autopilot
195
    // but only the camera.
196
}
1✔
197

198
void CameraImpl::manual_enable()
×
199
{
200
    refresh_params();
×
201

202
    request_status();
×
203
    request_camera_information();
×
204

205
    _system_impl->add_call_every(
×
206
        [this]() { request_camera_information(); }, 10.0, &_camera_information_call_every_cookie);
×
207

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

210
    // for backwards compatibility with Yuneec drones
211
    if (_system_impl->has_autopilot()) {
×
212
        request_flight_information();
×
213

214
        _system_impl->add_call_every(
×
215
            [this]() { request_flight_information(); },
×
216
            10.0,
217
            &_flight_information_call_every_cookie);
218
    }
219
}
×
220

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

228
void CameraImpl::manual_disable()
×
229
{
230
    invalidate_params();
×
231
    _system_impl->remove_call_every(_camera_information_call_every_cookie);
×
232
    _system_impl->remove_call_every(_status.call_every_cookie);
×
233

234
    if (_flight_information_call_every_cookie) {
×
235
        _system_impl->remove_call_every(_flight_information_call_every_cookie);
×
236
    }
237

238
    _camera_found = false;
×
239
}
×
240

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

247
    _system_impl->update_component_id_messages_handler(
×
248
        MAVLINK_MSG_ID_STORAGE_INFORMATION, cmp_id, this);
249

250
    _system_impl->update_component_id_messages_handler(
×
251
        MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, cmp_id, this);
252

253
    _system_impl->update_component_id_messages_handler(
×
254
        MAVLINK_MSG_ID_CAMERA_SETTINGS, cmp_id, this);
255

256
    _system_impl->update_component_id_messages_handler(
×
257
        MAVLINK_MSG_ID_CAMERA_INFORMATION, cmp_id, this);
258

259
    _system_impl->update_component_id_messages_handler(
×
260
        MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, cmp_id, this);
261

262
    _system_impl->update_component_id_messages_handler(
×
263
        MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, cmp_id, this);
264
}
×
265

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

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

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

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

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

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

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

294
    return command_flight_information;
×
295
}
296

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

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

305
    return command_camera_info;
×
306
}
307

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

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

320
    return cmd_take_photo;
×
321
}
322

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

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

330
    return cmd_stop_photo;
×
331
}
332

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

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

342
    return cmd_start_video;
×
343
}
344

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

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

353
    return cmd_stop_video;
×
354
}
355

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

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

365
    return cmd_set_camera_mode;
×
366
}
367

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

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

376
    return cmd_req_camera_settings;
×
377
}
378

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

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

387
    return cmd_req_camera_cap_stat;
×
388
}
389

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

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

401
    return cmd_req_camera_image_captured;
×
402
}
403

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

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

413
    return cmd_req_storage_info;
×
414
}
415

NEW
416
MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video_streaming(int32_t stream_id)
×
417
{
418
    MavlinkCommandSender::CommandLong cmd_start_video_streaming{};
×
419

420
    cmd_start_video_streaming.command = MAV_CMD_VIDEO_START_STREAMING;
×
NEW
421
    cmd_start_video_streaming.params.maybe_param1 = static_cast<float>(stream_id);
×
UNCOV
422
    cmd_start_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
423

424
    return cmd_start_video_streaming;
×
425
}
426

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

431
    cmd_stop_video_streaming.command = MAV_CMD_VIDEO_STOP_STREAMING;
×
NEW
432
    cmd_stop_video_streaming.params.maybe_param1 = static_cast<float>(stream_id);
×
UNCOV
433
    cmd_stop_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
434

435
    return cmd_stop_video_streaming;
×
436
}
437

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

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

446
    return cmd_req_video_stream_info;
×
447
}
448

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

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

457
    return cmd_req_video_stream_status;
×
458
}
459

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

592
    return _information.data;
×
593
}
594

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

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

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

UNCOV
616
    return handle;
×
617
}
618

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

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

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

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

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

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

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

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

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

672
    return _video_stream_info.data;
×
673
}
674

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

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

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

689
    return handle;
×
690
}
691

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

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

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

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

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

766
    return camera_result;
×
767
}
768

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

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

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

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

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

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

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

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

855
    notify_mode();
×
856

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

864
    return handle;
×
865
}
866

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

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

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

890
Camera::StatusHandle CameraImpl::subscribe_status(const Camera::StatusCallback& callback)
×
891
{
892
    std::lock_guard<std::mutex> lock(_status.mutex);
×
893
    auto handle = _status.subscription_callbacks.subscribe(callback);
×
894

895
    return handle;
×
896
}
897

898
void CameraImpl::unsubscribe_status(Camera::StatusHandle handle)
×
899
{
900
    std::lock_guard<std::mutex> lock(_status.mutex);
×
901
    _status.subscription_callbacks.unsubscribe(handle);
×
902
}
×
903

904
Camera::Status CameraImpl::status()
×
905
{
906
    std::lock_guard<std::mutex> lock(_status.mutex);
×
907
    return _status.data;
×
908
}
909

910
Camera::CaptureInfoHandle
911
CameraImpl::subscribe_capture_info(const Camera::CaptureInfoCallback& callback)
×
912
{
913
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
914
    return _capture_info.callbacks.subscribe(callback);
×
915
}
916

917
void CameraImpl::unsubscribe_capture_info(Camera::CaptureInfoHandle handle)
×
918
{
919
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
920
    _capture_info.callbacks.unsubscribe(handle);
×
921
}
×
922

923
void CameraImpl::process_camera_capture_status(const mavlink_message_t& message)
×
924
{
925
    mavlink_camera_capture_status_t camera_capture_status;
×
926
    mavlink_msg_camera_capture_status_decode(&message, &camera_capture_status);
×
927

928
    // If image_count got smaller, consider that the storage was formatted.
929
    if (camera_capture_status.image_count < _status.image_count) {
×
930
        LogDebug() << "Seems like storage was formatted, setting state accordingly";
×
931
        reset_following_format_storage();
×
932
    }
933

934
    {
935
        std::lock_guard<std::mutex> lock(_status.mutex);
×
936

937
        _status.data.video_on = (camera_capture_status.video_status == 1);
×
938
        _status.data.photo_interval_on =
×
939
            (camera_capture_status.image_status == 2 || camera_capture_status.image_status == 3);
×
940
        _status.received_camera_capture_status = true;
×
941
        _status.data.recording_time_s = float(camera_capture_status.recording_time_ms) / 1e3f;
×
942

943
        _status.image_count = camera_capture_status.image_count;
×
944

945
        if (_status.image_count_at_connection == -1) {
×
946
            _status.image_count_at_connection = camera_capture_status.image_count;
×
947
        }
948
    }
949

950
    check_status();
×
951
}
×
952

953
void CameraImpl::process_storage_information(const mavlink_message_t& message)
×
954
{
955
    mavlink_storage_information_t storage_information;
×
956
    mavlink_msg_storage_information_decode(&message, &storage_information);
×
957

958
    if (storage_information.total_capacity == 0.0f) {
×
959
        // Some MAVLink systems happen to send the STORAGE_INFORMATION message
960
        // to indicate that the camera has a slot for a storage even if there
961
        // is no way to know anything about that storage (e.g. whether or not
962
        // there is an sdcard in the slot).
963
        //
964
        // We consider that a total capacity of 0 means that this is such a
965
        // message, and we don't expect MAVSDK users to leverage it, which is
966
        // why it is ignored.
967
        return;
×
968
    }
969

970
    {
971
        std::lock_guard<std::mutex> lock(_status.mutex);
×
972
        _status.data.storage_status = storage_status_from_mavlink(storage_information.status);
×
973
        _status.data.available_storage_mib = storage_information.available_capacity;
×
974
        _status.data.used_storage_mib = storage_information.used_capacity;
×
975
        _status.data.total_storage_mib = storage_information.total_capacity;
×
976
        _status.data.storage_id = storage_information.storage_id;
×
977
        _status.data.storage_type = storage_type_from_mavlink(storage_information.type);
×
978
        _status.received_storage_information = true;
×
979
    }
980

981
    check_status();
×
982
}
983

984
Camera::Status::StorageStatus
985
CameraImpl::storage_status_from_mavlink(const int storage_status) const
×
986
{
987
    switch (storage_status) {
×
988
        case STORAGE_STATUS_EMPTY:
×
989
            return Camera::Status::StorageStatus::NotAvailable;
×
990
        case STORAGE_STATUS_UNFORMATTED:
×
991
            return Camera::Status::StorageStatus::Unformatted;
×
992
        case STORAGE_STATUS_READY:
×
993
            return Camera::Status::StorageStatus::Formatted;
×
994
            break;
995
        case STORAGE_STATUS_NOT_SUPPORTED:
×
996
            return Camera::Status::StorageStatus::NotSupported;
×
997
        default:
×
998
            LogErr() << "Unknown storage status received.";
×
999
            return Camera::Status::StorageStatus::NotSupported;
×
1000
    }
1001
}
1002

1003
Camera::Status::StorageType CameraImpl::storage_type_from_mavlink(const int storage_type) const
×
1004
{
1005
    switch (storage_type) {
×
1006
        default:
×
1007
            LogErr() << "Unknown storage_type enum value: " << storage_type;
×
1008
        // FALLTHROUGH
1009
        case STORAGE_TYPE_UNKNOWN:
×
1010
            return mavsdk::Camera::Status::StorageType::Unknown;
×
1011
        case STORAGE_TYPE_USB_STICK:
×
1012
            return mavsdk::Camera::Status::StorageType::UsbStick;
×
1013
        case STORAGE_TYPE_SD:
×
1014
            return mavsdk::Camera::Status::StorageType::Sd;
×
1015
        case STORAGE_TYPE_MICROSD:
×
1016
            return mavsdk::Camera::Status::StorageType::Microsd;
×
1017
        case STORAGE_TYPE_HD:
×
1018
            return mavsdk::Camera::Status::StorageType::Hd;
×
1019
        case STORAGE_TYPE_OTHER:
×
1020
            return mavsdk::Camera::Status::StorageType::Other;
×
1021
    }
1022
}
1023

1024
void CameraImpl::process_camera_image_captured(const mavlink_message_t& message)
×
1025
{
1026
    mavlink_camera_image_captured_t image_captured;
×
1027
    mavlink_msg_camera_image_captured_decode(&message, &image_captured);
×
1028

1029
    {
1030
        Camera::CaptureInfo capture_info = {};
×
1031
        capture_info.position.latitude_deg = image_captured.lat / 1e7;
×
1032
        capture_info.position.longitude_deg = image_captured.lon / 1e7;
×
1033
        capture_info.position.absolute_altitude_m = image_captured.alt / 1e3f;
×
1034
        capture_info.position.relative_altitude_m = image_captured.relative_alt / 1e3f;
×
1035
        capture_info.time_utc_us = image_captured.time_utc;
×
1036
        capture_info.attitude_quaternion.w = image_captured.q[0];
×
1037
        capture_info.attitude_quaternion.x = image_captured.q[1];
×
1038
        capture_info.attitude_quaternion.y = image_captured.q[2];
×
1039
        capture_info.attitude_quaternion.z = image_captured.q[3];
×
1040
        capture_info.attitude_euler_angle =
1041
            to_euler_angle_from_quaternion(capture_info.attitude_quaternion);
×
1042
        capture_info.file_url = std::string(image_captured.file_url);
×
1043
        capture_info.is_success = (image_captured.capture_result == 1);
×
1044
        capture_info.index = image_captured.image_index;
×
1045

1046
        _status.photo_list.insert(std::make_pair(image_captured.image_index, capture_info));
×
1047

1048
        _captured_request_cv.notify_all();
×
1049

1050
        std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1051
        // Notify user if a new image has been captured.
1052
        if (_capture_info.last_advertised_image_index < capture_info.index) {
×
1053
            _capture_info.callbacks.queue(
×
1054
                capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1055

1056
            if (_capture_info.last_advertised_image_index != -1) {
×
1057
                // Save captured indices that have been dropped to request later, however, don't
1058
                // do it from the very beginning as there might be many photos from a previous
1059
                // time that we don't want to request.
1060
                for (int i = _capture_info.last_advertised_image_index + 1; i < capture_info.index;
×
1061
                     ++i) {
1062
                    if (_capture_info.missing_image_retries.find(i) ==
×
1063
                        _capture_info.missing_image_retries.end()) {
×
1064
                        _capture_info.missing_image_retries[i] = 0;
×
1065
                    }
1066
                }
1067
            }
1068

1069
            _capture_info.last_advertised_image_index = capture_info.index;
×
1070
        }
1071

1072
        else if (auto it = _capture_info.missing_image_retries.find(capture_info.index);
×
1073
                 it != _capture_info.missing_image_retries.end()) {
×
1074
            _capture_info.callbacks.queue(
×
1075
                capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1076
            _capture_info.missing_image_retries.erase(it);
×
1077
        }
1078
    }
1079
}
×
1080

1081
void CameraImpl::request_missing_capture_info()
×
1082
{
1083
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1084

1085
    for (auto it = _capture_info.missing_image_retries.begin();
×
1086
         it != _capture_info.missing_image_retries.end();
×
1087
         /* ++it */) {
1088
        if (it->second > 3) {
×
1089
            it = _capture_info.missing_image_retries.erase(it);
×
1090
        } else {
1091
            ++it;
×
1092
        }
1093
    }
1094

1095
    if (!_capture_info.missing_image_retries.empty()) {
×
1096
        auto it_lowest_retries = std::min_element(
×
1097
            _capture_info.missing_image_retries.begin(), _capture_info.missing_image_retries.end());
×
1098
        _system_impl->send_command_async(
×
1099
            CameraImpl::make_command_request_camera_image_captured(it_lowest_retries->first),
×
1100
            nullptr);
1101
        it_lowest_retries->second += 1;
×
1102
    }
1103
}
×
1104

1105
Camera::EulerAngle CameraImpl::to_euler_angle_from_quaternion(Camera::Quaternion quaternion)
×
1106
{
1107
    auto& q = quaternion;
×
1108

1109
    // FIXME: This is duplicated from telemetry/math_conversions.cpp.
1110
    Camera::EulerAngle euler_angle;
×
1111
    euler_angle.roll_deg = to_deg_from_rad(
×
1112
        atan2f(2.0f * (q.w * q.x + q.y * q.z), 1.0f - 2.0f * (q.x * q.x + q.y * q.y)));
×
1113

1114
    euler_angle.pitch_deg = to_deg_from_rad(asinf(2.0f * (q.w * q.y - q.z * q.x)));
×
1115
    euler_angle.yaw_deg = to_deg_from_rad(
×
1116
        atan2f(2.0f * (q.w * q.z + q.x * q.y), 1.0f - 2.0f * (q.y * q.y + q.z * q.z)));
×
1117
    return euler_angle;
×
1118
}
1119

1120
void CameraImpl::process_camera_settings(const mavlink_message_t& message)
×
1121
{
1122
    mavlink_camera_settings_t camera_settings;
×
1123
    mavlink_msg_camera_settings_decode(&message, &camera_settings);
×
1124

1125
    {
1126
        std::lock_guard<std::mutex> lock(_mode.mutex);
×
1127
        _mode.data = to_camera_mode(camera_settings.mode_id);
×
1128
    }
1129
    notify_mode();
×
1130

1131
    if (_camera_definition) {
×
1132
        // This "parameter" needs to be manually set.
1133
        save_camera_mode(camera_settings.mode_id);
×
1134
    }
1135
}
×
1136

1137
Camera::Mode CameraImpl::to_camera_mode(const uint8_t mavlink_camera_mode) const
×
1138
{
1139
    switch (mavlink_camera_mode) {
×
1140
        case CAMERA_MODE_IMAGE:
×
1141
            return Camera::Mode::Photo;
×
1142
        case CAMERA_MODE_VIDEO:
×
1143
            return Camera::Mode::Video;
×
1144
        default:
×
1145
            return Camera::Mode::Unknown;
×
1146
    }
1147
}
1148

1149
void CameraImpl::process_camera_information(const mavlink_message_t& message)
×
1150
{
1151
    mavlink_camera_information_t camera_information;
×
1152
    mavlink_msg_camera_information_decode(&message, &camera_information);
×
1153

1154
    // Make sure all strings are zero terminated, so we don't overrun anywhere.
1155
    camera_information.vendor_name[sizeof(camera_information.vendor_name) - 1] = '\0';
×
1156
    camera_information.model_name[sizeof(camera_information.model_name) - 1] = '\0';
×
1157
    camera_information.cam_definition_uri[sizeof(camera_information.cam_definition_uri) - 1] = '\0';
×
1158

1159
    std::lock_guard<std::mutex> lock(_information.mutex);
×
1160

1161
    _information.data.vendor_name = (char*)(camera_information.vendor_name);
×
1162
    _information.data.model_name = (char*)(camera_information.model_name);
×
1163
    _information.data.focal_length_mm = camera_information.focal_length;
×
1164
    _information.data.horizontal_sensor_size_mm = camera_information.sensor_size_h;
×
1165
    _information.data.vertical_sensor_size_mm = camera_information.sensor_size_v;
×
1166
    _information.data.horizontal_resolution_px = camera_information.resolution_h;
×
1167
    _information.data.vertical_resolution_px = camera_information.resolution_v;
×
1168

1169
    _information.subscription_callbacks.queue(
×
1170
        _information.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1171

1172
    if (should_fetch_camera_definition(camera_information.cam_definition_uri)) {
×
1173
        _is_fetching_camera_definition = true;
×
1174

1175
        std::thread([this, camera_information]() {
×
1176
            std::string content{};
×
1177
            const auto result = fetch_camera_definition(camera_information, content);
×
1178

1179
            if (result == Camera::Result::Success) {
×
1180
                LogDebug() << "Successfully loaded camera definition";
×
1181

1182
                if (_camera_definition_callback) {
×
1183
                    _system_impl->call_user_callback(
×
1184
                        [this, result]() { _camera_definition_callback(result); });
1185
                }
1186

1187
                _camera_definition.reset(new CameraDefinition());
×
1188
                _camera_definition->load_string(content);
×
1189
                refresh_params();
×
1190

1191
            } else if (result == Camera::Result::ProtocolUnsupported) {
×
1192
                LogWarn() << "Protocol for " << camera_information.cam_definition_uri
×
1193
                          << " not supported";
×
1194
                if (_camera_definition_callback) {
×
1195
                    _system_impl->call_user_callback(
×
1196
                        [this, result]() { _camera_definition_callback(result); });
1197
                }
1198

1199
            } else {
1200
                LogDebug() << "Failed to fetch camera definition!";
×
1201

1202
                if (++_camera_definition_fetch_count >= 3) {
×
1203
                    LogWarn() << "Giving up fetching the camera definition";
×
1204

1205
                    std::lock_guard<std::mutex> thread_lock(_information.mutex);
×
1206
                    _has_camera_definition_timed_out = true;
×
1207

1208
                    if (_camera_definition_callback) {
×
1209
                        _system_impl->call_user_callback(
×
1210
                            [this, result]() { _camera_definition_callback(result); });
1211
                    }
1212
                }
1213
            }
1214

1215
            std::lock_guard<std::mutex> thread_lock(_information.mutex);
×
1216
            _is_fetching_camera_definition = false;
×
1217
        }).detach();
×
1218
    }
1219
}
×
1220

1221
bool CameraImpl::should_fetch_camera_definition(const std::string& uri) const
×
1222
{
1223
    return !uri.empty() && !_camera_definition && !_is_fetching_camera_definition &&
×
1224
           !_has_camera_definition_timed_out;
×
1225
}
1226

1227
Camera::Result CameraImpl::fetch_camera_definition(
×
1228
    const mavlink_camera_information_t& camera_information, std::string& camera_definition_out)
1229
{
1230
    auto result =
1231
        download_definition_file(camera_information.cam_definition_uri, camera_definition_out);
×
1232

1233
    return result;
×
1234
}
1235

1236
Camera::Result
1237
CameraImpl::download_definition_file(const std::string& uri, std::string& camera_definition_out)
×
1238
{
1239
#if BUILD_WITHOUT_CURL == 1
1240
    UNUSED(uri);
1241
    UNUSED(camera_definition_out);
1242
    return Camera::Result::ProtocolUnsupported;
1243
#else
1244
    HttpLoader http_loader;
×
1245
    LogInfo() << "Downloading camera definition from: " << uri;
×
1246
    if (!http_loader.download_text_sync(uri, camera_definition_out)) {
×
1247
        LogErr() << "Failed to download camera definition.";
×
1248
        return Camera::Result::Error;
×
1249
    }
1250
#endif
1251

1252
    return Camera::Result::Success;
×
1253
}
1254

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

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

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

1283
    notify_video_stream_info();
×
1284
}
×
1285

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

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

1312
    notify_video_stream_info();
×
1313
}
×
1314

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1524
        if (all_values.size() == 0) {
×
1525
            if (callback) {
×
1526
                LogErr() << "Could not get any options to get type for range param.";
×
1527
                const auto temp_callback = callback;
×
1528
                _system_impl->call_user_callback(
×
1529
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1530
            }
1531
            return;
×
1532
        }
1533
        value = all_values[0];
×
1534
        // Now re-use that type.
1535
        // FIXME: this is quite ugly, we should do better than that.
1536
        if (!value.set_as_same_type(option.option_id)) {
×
1537
            if (callback) {
×
1538
                LogErr() << "Could not set option value to given type.";
×
1539
                const auto temp_callback = callback;
×
1540
                _system_impl->call_user_callback(
×
1541
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1542
            }
1543
            return;
×
1544
        }
1545

1546
    } else {
1547
        if (!_camera_definition->get_option_value(setting_id, option.option_id, value)) {
×
1548
            if (callback) {
×
1549
                LogErr() << "Could not get option value.";
×
1550
                const auto temp_callback = callback;
×
1551
                _system_impl->call_user_callback(
×
1552
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1553
            }
1554
            return;
×
1555
        }
1556

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

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

1590
                if (!_camera_definition->set_setting(setting_id, value)) {
×
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
                if (callback) {
×
1600
                    const auto temp_callback = callback;
×
1601
                    _system_impl->call_user_callback(
×
1602
                        [temp_callback]() { temp_callback(Camera::Result::Success); });
1603
                }
1604

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1833
    return results;
1834
}
1835

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

NEW
1937
    format_storage_async(storage_id, [prom](Camera::Result result) { prom->set_value(result); });
×
1938

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

NEW
1942
void CameraImpl::format_storage_async(int32_t storage_id, Camera::ResultCallback callback)
×
1943
{
1944
    MavlinkCommandSender::CommandLong cmd_format{};
×
1945

1946
    cmd_format.command = MAV_CMD_STORAGE_FORMAT;
×
NEW
1947
    cmd_format.params.maybe_param1 = static_cast<float>(storage_id); // storage ID
×
1948
    cmd_format.params.maybe_param2 = 1.0f; // format
×
1949
    cmd_format.params.maybe_param3 = 1.0f; // clear
×
1950
    cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
1951

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

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

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

NEW
1966
Camera::Result CameraImpl::reset_settings()
×
1967
{
NEW
1968
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
NEW
1969
    auto ret = prom->get_future();
×
1970

NEW
1971
    reset_settings_async([prom](Camera::Result result) { prom->set_value(result); });
×
1972

NEW
1973
    return ret.get();
×
1974
}
NEW
1975
void CameraImpl::reset_settings_async(const Camera::ResultCallback callback)
×
1976
{
NEW
1977
    MavlinkCommandSender::CommandLong cmd_format{};
×
1978

NEW
1979
    cmd_format.command = MAV_CMD_RESET_CAMERA_SETTINGS;
×
NEW
1980
    cmd_format.params.maybe_param1 = 1.0f; // reset
×
NEW
1981
    cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
1982

NEW
1983
    _system_impl->send_command_async(
×
NEW
1984
        cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
×
NEW
1985
            UNUSED(progress);
×
1986

NEW
1987
            receive_command_result(result, [this, callback](Camera::Result camera_result) {
×
NEW
1988
                callback(camera_result);
×
NEW
1989
            });
×
NEW
1990
        });
×
NEW
1991
}
×
1992

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

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

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

2019
    return ret.get();
×
2020
}
2021

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

2030
    {
2031
        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2032

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

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

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

2063
    std::thread([this, start_index, callback]() {
×
2064
        std::unique_lock<std::mutex> capture_request_lock(_captured_request_mutex);
×
2065

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

2072
            while (_status.photo_list.find(i) == _status.photo_list.end() &&
×
2073
                   safety_count < safety_count_boundary) {
2074
                safety_count++;
×
2075

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

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

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

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

2109
        std::vector<Camera::CaptureInfo> photo_list;
×
2110
        {
2111
            std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2112

2113
            for (auto capture_info : _status.photo_list) {
×
2114
                if (capture_info.first >= start_index) {
×
2115
                    photo_list.push_back(capture_info.second);
×
2116
                }
2117
            }
2118

2119
            _status.is_fetching_photos = false;
×
2120

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

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

© 2026 Coveralls, Inc