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

mavlink / MAVSDK / 7238188264

17 Dec 2023 11:27AM UTC coverage: 37.138% (+0.05%) from 37.088%
7238188264

push

github

web-flow
Merge pull request #2195 from mavlink/pr-remove-cached-camera-defs

camera: remove cached camera definition files

0 of 1 new or added line in 1 file covered. (0.0%)

2 existing lines in 1 file now uncovered.

10003 of 26935 relevant lines covered (37.14%)

113.49 hits per line

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

4.87
/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

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

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

423
    return cmd_start_video_streaming;
×
424
}
425

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

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

433
    return cmd_stop_video_streaming;
×
434
}
435

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

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

444
    return cmd_req_video_stream_info;
×
445
}
446

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

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

455
    return cmd_req_video_stream_status;
×
456
}
457

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

590
    return _information.data;
×
591
}
592

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

599
    return handle;
×
600
}
601

602
void CameraImpl::unsubscribe_information(Camera::InformationHandle handle)
×
603
{
604
    std::lock_guard<std::mutex> lock(_information.mutex);
×
605
    _information.subscription_callbacks.unsubscribe(handle);
×
606
}
×
607

608
Camera::Result CameraImpl::start_video_streaming()
×
609
{
610
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
611

612
    if (_video_stream_info.available &&
×
613
        _video_stream_info.data.status == Camera::VideoStreamInfo::VideoStreamStatus::InProgress) {
×
614
        return Camera::Result::InProgress;
×
615
    }
616

617
    // TODO Check whether we're in video mode
618
    auto command = make_command_start_video_streaming();
×
619

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

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

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

645
void CameraImpl::request_video_stream_info()
×
646
{
647
    _system_impl->send_command_async(make_command_request_video_stream_info(), nullptr);
×
648
    _system_impl->send_command_async(make_command_request_video_stream_status(), nullptr);
×
649
}
×
650

651
Camera::VideoStreamInfo CameraImpl::video_stream_info()
×
652
{
653
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
654

655
    return _video_stream_info.data;
×
656
}
657

658
Camera::VideoStreamInfoHandle
659
CameraImpl::subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& callback)
×
660
{
661
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
662

663
    auto handle = _video_stream_info.subscription_callbacks.subscribe(callback);
×
664

665
    if (callback) {
×
666
        _system_impl->add_call_every(
×
667
            [this]() { request_video_stream_info(); }, 1.0, &_video_stream_info.call_every_cookie);
×
668
    } else {
669
        _system_impl->remove_call_every(_video_stream_info.call_every_cookie);
×
670
    }
671

672
    return handle;
×
673
}
674

675
void CameraImpl::unsubscribe_video_stream_info(Camera::VideoStreamInfoHandle handle)
×
676
{
677
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
678
    _video_stream_info.subscription_callbacks.unsubscribe(handle);
×
679
}
×
680

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

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

731
Camera::Result CameraImpl::set_mode(const Camera::Mode mode)
×
732
{
733
    const float mavlink_mode = to_mavlink_camera_mode(mode);
×
734
    auto cmd_set_camera_mode = make_command_set_camera_mode(mavlink_mode);
×
735
    const auto command_result = _system_impl->send_command(cmd_set_camera_mode);
×
736
    const auto camera_result = camera_result_from_command_result(command_result);
×
737

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

749
    return camera_result;
×
750
}
751

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

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

796
    _camera_definition->set_setting("CAM_MODE", value);
×
797
    refresh_params();
×
798
}
799

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

813
void CameraImpl::set_mode_async(const Camera::Mode mode, const Camera::ResultCallback& callback)
×
814
{
815
    const auto mavlink_mode = to_mavlink_camera_mode(mode);
×
816
    auto cmd_set_camera_mode = make_command_set_camera_mode(mavlink_mode);
×
817

818
    _system_impl->send_command_async(
×
819
        cmd_set_camera_mode,
820
        [this, callback, mode](MavlinkCommandSender::Result result, float progress) {
×
821
            UNUSED(progress);
×
822
            receive_set_mode_command_result(result, callback, mode);
×
823
        });
×
824
}
×
825

826
Camera::Mode CameraImpl::mode()
×
827
{
828
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
829
    return _mode.data;
×
830
}
831

832
Camera::ModeHandle CameraImpl::subscribe_mode(const Camera::ModeCallback& callback)
×
833
{
834
    std::unique_lock<std::mutex> lock(_mode.mutex);
×
835
    auto handle = _mode.subscription_callbacks.subscribe(callback);
×
836
    lock.unlock();
×
837

838
    notify_mode();
×
839

840
    if (callback) {
×
841
        _system_impl->add_call_every(
×
842
            [this]() { request_camera_settings(); }, 5.0, &_mode.call_every_cookie);
×
843
    } else {
844
        _system_impl->remove_call_every(_mode.call_every_cookie);
×
845
    }
846

847
    return handle;
×
848
}
849

850
void CameraImpl::unsubscribe_mode(Camera::ModeHandle handle)
×
851
{
852
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
853
    _mode.subscription_callbacks.unsubscribe(handle);
×
854
}
×
855

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

867
void CameraImpl::request_status()
×
868
{
869
    _system_impl->send_command_async(make_command_request_camera_capture_status(), nullptr);
×
870
    _system_impl->send_command_async(make_command_request_storage_info(), nullptr);
×
871
}
×
872

873
Camera::StatusHandle CameraImpl::subscribe_status(const Camera::StatusCallback& callback)
×
874
{
875
    std::lock_guard<std::mutex> lock(_status.mutex);
×
876
    auto handle = _status.subscription_callbacks.subscribe(callback);
×
877

878
    return handle;
×
879
}
880

881
void CameraImpl::unsubscribe_status(Camera::StatusHandle handle)
×
882
{
883
    std::lock_guard<std::mutex> lock(_status.mutex);
×
884
    _status.subscription_callbacks.unsubscribe(handle);
×
885
}
×
886

887
Camera::Status CameraImpl::status()
×
888
{
889
    std::lock_guard<std::mutex> lock(_status.mutex);
×
890
    return _status.data;
×
891
}
892

893
Camera::CaptureInfoHandle
894
CameraImpl::subscribe_capture_info(const Camera::CaptureInfoCallback& callback)
×
895
{
896
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
897
    return _capture_info.callbacks.subscribe(callback);
×
898
}
899

900
void CameraImpl::unsubscribe_capture_info(Camera::CaptureInfoHandle handle)
×
901
{
902
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
903
    _capture_info.callbacks.unsubscribe(handle);
×
904
}
×
905

906
void CameraImpl::process_camera_capture_status(const mavlink_message_t& message)
×
907
{
908
    mavlink_camera_capture_status_t camera_capture_status;
×
909
    mavlink_msg_camera_capture_status_decode(&message, &camera_capture_status);
×
910

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

917
    {
918
        std::lock_guard<std::mutex> lock(_status.mutex);
×
919

920
        _status.data.video_on = (camera_capture_status.video_status == 1);
×
921
        _status.data.photo_interval_on =
×
922
            (camera_capture_status.image_status == 2 || camera_capture_status.image_status == 3);
×
923
        _status.received_camera_capture_status = true;
×
924
        _status.data.recording_time_s = float(camera_capture_status.recording_time_ms) / 1e3f;
×
925

926
        _status.image_count = camera_capture_status.image_count;
×
927

928
        if (_status.image_count_at_connection == -1) {
×
929
            _status.image_count_at_connection = camera_capture_status.image_count;
×
930
        }
931
    }
932

933
    check_status();
×
934
}
×
935

936
void CameraImpl::process_storage_information(const mavlink_message_t& message)
×
937
{
938
    mavlink_storage_information_t storage_information;
×
939
    mavlink_msg_storage_information_decode(&message, &storage_information);
×
940

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

953
    {
954
        std::lock_guard<std::mutex> lock(_status.mutex);
×
955
        _status.data.storage_status = storage_status_from_mavlink(storage_information.status);
×
956
        _status.data.available_storage_mib = storage_information.available_capacity;
×
957
        _status.data.used_storage_mib = storage_information.used_capacity;
×
958
        _status.data.total_storage_mib = storage_information.total_capacity;
×
959
        _status.data.storage_id = storage_information.storage_id;
×
960
        _status.data.storage_type = storage_type_from_mavlink(storage_information.type);
×
961
        _status.received_storage_information = true;
×
962
    }
963

964
    check_status();
×
965
}
966

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

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

1007
void CameraImpl::process_camera_image_captured(const mavlink_message_t& message)
×
1008
{
1009
    mavlink_camera_image_captured_t image_captured;
×
1010
    mavlink_msg_camera_image_captured_decode(&message, &image_captured);
×
1011

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

1029
        _status.photo_list.insert(std::make_pair(image_captured.image_index, capture_info));
×
1030

1031
        _captured_request_cv.notify_all();
×
1032

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

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

1052
            _capture_info.last_advertised_image_index = capture_info.index;
×
1053
        }
1054

1055
        else if (auto it = _capture_info.missing_image_retries.find(capture_info.index);
×
1056
                 it != _capture_info.missing_image_retries.end()) {
×
1057
            _capture_info.callbacks.queue(
×
1058
                capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1059
            _capture_info.missing_image_retries.erase(it);
×
1060
        }
1061
    }
1062
}
×
1063

1064
void CameraImpl::request_missing_capture_info()
×
1065
{
1066
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1067

1068
    for (auto it = _capture_info.missing_image_retries.begin();
×
1069
         it != _capture_info.missing_image_retries.end();
×
1070
         /* ++it */) {
1071
        if (it->second > 3) {
×
1072
            it = _capture_info.missing_image_retries.erase(it);
×
1073
        } else {
1074
            ++it;
×
1075
        }
1076
    }
1077

1078
    if (!_capture_info.missing_image_retries.empty()) {
×
1079
        auto it_lowest_retries = std::min_element(
×
1080
            _capture_info.missing_image_retries.begin(), _capture_info.missing_image_retries.end());
×
1081
        _system_impl->send_command_async(
×
1082
            CameraImpl::make_command_request_camera_image_captured(it_lowest_retries->first),
×
1083
            nullptr);
1084
        it_lowest_retries->second += 1;
×
1085
    }
1086
}
×
1087

1088
Camera::EulerAngle CameraImpl::to_euler_angle_from_quaternion(Camera::Quaternion quaternion)
×
1089
{
1090
    auto& q = quaternion;
×
1091

1092
    // FIXME: This is duplicated from telemetry/math_conversions.cpp.
1093
    Camera::EulerAngle euler_angle;
×
1094
    euler_angle.roll_deg = to_deg_from_rad(
×
1095
        atan2f(2.0f * (q.w * q.x + q.y * q.z), 1.0f - 2.0f * (q.x * q.x + q.y * q.y)));
×
1096

1097
    euler_angle.pitch_deg = to_deg_from_rad(asinf(2.0f * (q.w * q.y - q.z * q.x)));
×
1098
    euler_angle.yaw_deg = to_deg_from_rad(
×
1099
        atan2f(2.0f * (q.w * q.z + q.x * q.y), 1.0f - 2.0f * (q.y * q.y + q.z * q.z)));
×
1100
    return euler_angle;
×
1101
}
1102

1103
void CameraImpl::process_camera_settings(const mavlink_message_t& message)
×
1104
{
1105
    mavlink_camera_settings_t camera_settings;
×
1106
    mavlink_msg_camera_settings_decode(&message, &camera_settings);
×
1107

1108
    {
1109
        std::lock_guard<std::mutex> lock(_mode.mutex);
×
1110
        _mode.data = to_camera_mode(camera_settings.mode_id);
×
1111
    }
1112
    notify_mode();
×
1113

1114
    if (_camera_definition) {
×
1115
        // This "parameter" needs to be manually set.
1116
        save_camera_mode(camera_settings.mode_id);
×
1117
    }
1118
}
×
1119

1120
Camera::Mode CameraImpl::to_camera_mode(const uint8_t mavlink_camera_mode) const
×
1121
{
1122
    switch (mavlink_camera_mode) {
×
1123
        case CAMERA_MODE_IMAGE:
×
1124
            return Camera::Mode::Photo;
×
1125
        case CAMERA_MODE_VIDEO:
×
1126
            return Camera::Mode::Video;
×
1127
        default:
×
1128
            return Camera::Mode::Unknown;
×
1129
    }
1130
}
1131

1132
void CameraImpl::process_camera_information(const mavlink_message_t& message)
×
1133
{
1134
    mavlink_camera_information_t camera_information;
×
1135
    mavlink_msg_camera_information_decode(&message, &camera_information);
×
1136

1137
    // Make sure all strings are zero terminated, so we don't overrun anywhere.
1138
    camera_information.vendor_name[sizeof(camera_information.vendor_name) - 1] = '\0';
×
1139
    camera_information.model_name[sizeof(camera_information.model_name) - 1] = '\0';
×
1140
    camera_information.cam_definition_uri[sizeof(camera_information.cam_definition_uri) - 1] = '\0';
×
1141

1142
    std::lock_guard<std::mutex> lock(_information.mutex);
×
1143

1144
    _information.data.vendor_name = (char*)(camera_information.vendor_name);
×
1145
    _information.data.model_name = (char*)(camera_information.model_name);
×
1146
    _information.data.focal_length_mm = camera_information.focal_length;
×
1147
    _information.data.horizontal_sensor_size_mm = camera_information.sensor_size_h;
×
1148
    _information.data.vertical_sensor_size_mm = camera_information.sensor_size_v;
×
1149
    _information.data.horizontal_resolution_px = camera_information.resolution_h;
×
1150
    _information.data.vertical_resolution_px = camera_information.resolution_v;
×
1151

1152
    _information.subscription_callbacks.queue(
×
1153
        _information.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1154

1155
    if (should_fetch_camera_definition(camera_information.cam_definition_uri)) {
×
1156
        _is_fetching_camera_definition = true;
×
1157

1158
        std::thread([this, camera_information]() {
×
1159
            std::string content{};
×
1160
            const auto result = fetch_camera_definition(camera_information, content);
×
1161

1162
            if (result == Camera::Result::Success) {
×
1163
                LogDebug() << "Successfully loaded camera definition";
×
1164

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

1170
                _camera_definition.reset(new CameraDefinition());
×
1171
                _camera_definition->load_string(content);
×
1172
                refresh_params();
×
1173

1174
            } else if (result == Camera::Result::ProtocolUnsupported) {
×
1175
                LogWarn() << "Protocol for " << camera_information.cam_definition_uri
×
1176
                          << " not supported";
×
1177
                if (_camera_definition_callback) {
×
1178
                    _system_impl->call_user_callback(
×
1179
                        [this, result]() { _camera_definition_callback(result); });
1180
                }
1181

1182
            } else {
1183
                LogDebug() << "Failed to fetch camera definition!";
×
1184

1185
                if (++_camera_definition_fetch_count >= 3) {
×
1186
                    LogWarn() << "Giving up fetching the camera definition";
×
1187

1188
                    std::lock_guard<std::mutex> thread_lock(_information.mutex);
×
1189
                    _has_camera_definition_timed_out = true;
×
1190

1191
                    if (_camera_definition_callback) {
×
1192
                        _system_impl->call_user_callback(
×
1193
                            [this, result]() { _camera_definition_callback(result); });
1194
                    }
1195
                }
1196
            }
1197

1198
            std::lock_guard<std::mutex> thread_lock(_information.mutex);
×
1199
            _is_fetching_camera_definition = false;
×
1200
        }).detach();
×
1201
    }
1202
}
×
1203

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

1210
Camera::Result CameraImpl::fetch_camera_definition(
×
1211
    const mavlink_camera_information_t& camera_information, std::string& camera_definition_out)
1212
{
1213
    auto result =
1214
        download_definition_file(camera_information.cam_definition_uri, camera_definition_out);
×
1215

NEW
1216
    return result;
×
1217
}
1218

1219
Camera::Result
1220
CameraImpl::download_definition_file(const std::string& uri, std::string& camera_definition_out)
×
1221
{
1222
#if BUILD_WITHOUT_CURL == 1
1223
    UNUSED(uri);
1224
    UNUSED(camera_definition_out);
1225
    return Camera::Result::ProtocolUnsupported;
1226
#else
1227
    HttpLoader http_loader;
×
1228
    LogInfo() << "Downloading camera definition from: " << uri;
×
1229
    if (!http_loader.download_text_sync(uri, camera_definition_out)) {
×
1230
        LogErr() << "Failed to download camera definition.";
×
1231
        return Camera::Result::Error;
×
1232
    }
1233
#endif
1234

1235
    return Camera::Result::Success;
×
1236
}
1237

1238
void CameraImpl::process_video_information(const mavlink_message_t& message)
×
1239
{
1240
    mavlink_video_stream_information_t received_video_info;
×
1241
    mavlink_msg_video_stream_information_decode(&message, &received_video_info);
×
1242

1243
    {
1244
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1245
        // TODO: use stream_id and count
1246
        _video_stream_info.data.status =
×
1247
            (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
×
1248
                 Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1249
                 Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1250
        _video_stream_info.data.spectrum =
×
1251
            (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
×
1252
                 Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1253
                 Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1254

1255
        auto& video_stream_info = _video_stream_info.data.settings;
×
1256
        video_stream_info.frame_rate_hz = received_video_info.framerate;
×
1257
        video_stream_info.horizontal_resolution_pix = received_video_info.resolution_h;
×
1258
        video_stream_info.vertical_resolution_pix = received_video_info.resolution_v;
×
1259
        video_stream_info.bit_rate_b_s = received_video_info.bitrate;
×
1260
        video_stream_info.rotation_deg = received_video_info.rotation;
×
1261
        video_stream_info.horizontal_fov_deg = static_cast<float>(received_video_info.hfov);
×
1262
        video_stream_info.uri = received_video_info.uri;
×
1263
        _video_stream_info.available = true;
×
1264
    }
1265

1266
    notify_video_stream_info();
×
1267
}
×
1268

1269
void CameraImpl::process_video_stream_status(const mavlink_message_t& message)
×
1270
{
1271
    mavlink_video_stream_status_t received_video_stream_status;
×
1272
    mavlink_msg_video_stream_status_decode(&message, &received_video_stream_status);
×
1273
    {
1274
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1275
        _video_stream_info.data.status =
×
1276
            (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
×
1277
                 Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1278
                 Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1279
        _video_stream_info.data.spectrum =
×
1280
            (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
×
1281
                 Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1282
                 Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1283

1284
        auto& video_stream_info = _video_stream_info.data.settings;
×
1285
        video_stream_info.frame_rate_hz = received_video_stream_status.framerate;
×
1286
        video_stream_info.horizontal_resolution_pix = received_video_stream_status.resolution_h;
×
1287
        video_stream_info.vertical_resolution_pix = received_video_stream_status.resolution_v;
×
1288
        video_stream_info.bit_rate_b_s = received_video_stream_status.bitrate;
×
1289
        video_stream_info.rotation_deg = received_video_stream_status.rotation;
×
1290
        video_stream_info.horizontal_fov_deg =
×
1291
            static_cast<float>(received_video_stream_status.hfov);
×
1292
        _video_stream_info.available = true;
×
1293
    }
1294

1295
    notify_video_stream_info();
×
1296
}
×
1297

1298
void CameraImpl::process_flight_information(const mavlink_message_t& message)
×
1299
{
1300
    mavlink_flight_information_t flight_information;
×
1301
    mavlink_msg_flight_information_decode(&message, &flight_information);
×
1302

1303
    std::stringstream folder_name_stream;
×
1304
    {
1305
        std::lock_guard<std::mutex> information_lock(_information.mutex);
×
1306

1307
        // For Yuneec cameras, the folder names can be derived from the flight ID,
1308
        // starting at 100 up to 999.
1309
        if (_information.data.vendor_name == "Yuneec" && _information.data.model_name == "E90") {
×
1310
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "E90HD";
×
1311
        } else if (
×
1312
            _information.data.vendor_name == "Yuneec" && _information.data.model_name == "E50") {
×
1313
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "E50HD";
×
1314
        } else if (
×
1315
            _information.data.vendor_name == "Yuneec" && _information.data.model_name == "CGOET") {
×
1316
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "CGOET";
×
1317
        } else if (
×
1318
            _information.data.vendor_name == "Yuneec" && _information.data.model_name == "E10T") {
×
1319
            folder_name_stream << (101 + flight_information.flight_uuid % 899) << "E10T";
×
1320
        } else {
1321
            // Folder name unknown
1322
        }
1323
    }
1324

1325
    {
1326
        std::lock_guard<std::mutex> lock(_status.mutex);
×
1327
        _status.data.media_folder_name = folder_name_stream.str();
×
1328
    }
1329
}
×
1330

1331
void CameraImpl::notify_video_stream_info()
×
1332
{
1333
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1334

1335
    _video_stream_info.subscription_callbacks.queue(
×
1336
        _video_stream_info.data,
×
1337
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1338
}
×
1339

1340
void CameraImpl::check_status()
×
1341
{
1342
    std::lock_guard<std::mutex> lock(_status.mutex);
×
1343

1344
    if (_status.received_camera_capture_status && _status.received_storage_information) {
×
1345
        _status.subscription_callbacks.queue(
×
1346
            _status.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1347

1348
        _status.received_camera_capture_status = false;
×
1349
        _status.received_storage_information = false;
×
1350
    }
1351
}
×
1352

1353
void CameraImpl::receive_command_result(
×
1354
    MavlinkCommandSender::Result command_result, const Camera::ResultCallback& callback)
1355
{
1356
    Camera::Result camera_result = camera_result_from_command_result(command_result);
×
1357

1358
    if (callback) {
×
1359
        _system_impl->call_user_callback([callback, camera_result]() { callback(camera_result); });
×
1360
    }
1361
}
×
1362

1363
void CameraImpl::receive_set_mode_command_result(
×
1364
    const MavlinkCommandSender::Result command_result,
1365
    const Camera::ResultCallback callback,
1366
    const Camera::Mode mode)
1367
{
1368
    Camera::Result camera_result = camera_result_from_command_result(command_result);
×
1369

1370
    if (callback) {
×
1371
        const auto temp_callback = callback;
×
1372
        _system_impl->call_user_callback(
×
1373
            [temp_callback, camera_result]() { temp_callback(camera_result); });
1374
    }
1375

1376
    if (command_result == MavlinkCommandSender::Result::Success && _camera_definition) {
×
1377
        // This "parameter" needs to be manually set.
1378
        {
1379
            std::lock_guard<std::mutex> lock(_mode.mutex);
×
1380
            _mode.data = mode;
×
1381
        }
1382

1383
        const auto mavlink_mode = to_mavlink_camera_mode(mode);
×
1384

1385
        if (std::isnan(mavlink_mode)) {
×
1386
            LogWarn() << "Unknown camera mode";
×
1387
            return;
×
1388
        }
1389

1390
        notify_mode();
×
1391
        save_camera_mode(mavlink_mode);
×
1392
    }
1393
}
1394

1395
void CameraImpl::notify_mode()
×
1396
{
1397
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
1398

1399
    _mode.subscription_callbacks.queue(
×
1400
        _mode.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1401
}
×
1402

1403
bool CameraImpl::get_possible_setting_options(std::vector<std::string>& settings)
×
1404
{
1405
    settings.clear();
×
1406

1407
    if (!_camera_definition) {
×
1408
        LogWarn() << "Error: no camera definition available yet";
×
1409
        return false;
×
1410
    }
1411

1412
    std::unordered_map<std::string, ParamValue> cd_settings{};
×
1413
    _camera_definition->get_possible_settings(cd_settings);
×
1414

1415
    for (const auto& cd_setting : cd_settings) {
×
1416
        if (cd_setting.first == "CAM_MODE") {
×
1417
            // We ignore the mode param.
1418
            continue;
×
1419
        }
1420

1421
        settings.push_back(cd_setting.first);
×
1422
    }
1423

1424
    return settings.size() > 0;
×
1425
}
1426

1427
bool CameraImpl::get_possible_options(
×
1428
    const std::string& setting_id, std::vector<Camera::Option>& options)
1429
{
1430
    options.clear();
×
1431

1432
    if (!_camera_definition) {
×
1433
        LogWarn() << "Error: no camera definition available yet";
×
1434
        return false;
×
1435
    }
1436

1437
    std::vector<ParamValue> values;
×
1438
    if (!_camera_definition->get_possible_options(setting_id, values)) {
×
1439
        return false;
×
1440
    }
1441

1442
    for (const auto& value : values) {
×
1443
        std::stringstream ss{};
×
1444
        ss << value;
×
1445
        Camera::Option option{};
×
1446
        option.option_id = ss.str();
×
1447
        if (!is_setting_range(setting_id)) {
×
1448
            get_option_str(setting_id, option.option_id, option.option_description);
×
1449
        }
1450
        options.push_back(option);
×
1451
    }
1452

1453
    return options.size() > 0;
×
1454
}
1455

1456
bool CameraImpl::is_setting_range(const std::string& setting_id)
×
1457
{
1458
    return _camera_definition->is_setting_range(setting_id);
×
1459
}
1460

1461
Camera::Result CameraImpl::set_setting(Camera::Setting setting)
×
1462
{
1463
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1464
    auto ret = prom->get_future();
×
1465

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

1468
    return ret.get();
×
1469
}
1470

1471
void CameraImpl::set_setting_async(Camera::Setting setting, const Camera::ResultCallback callback)
×
1472
{
1473
    set_option_async(setting.setting_id, setting.option, callback);
×
1474
}
×
1475

1476
void CameraImpl::set_option_async(
×
1477
    const std::string& setting_id,
1478
    const Camera::Option& option,
1479
    const Camera::ResultCallback& callback)
1480
{
1481
    if (!_camera_definition) {
×
1482
        LogWarn() << "Error: no camera defnition available yet.";
×
1483
        if (callback) {
×
1484
            const auto temp_callback = callback;
×
1485
            _system_impl->call_user_callback(
×
1486
                [temp_callback]() { temp_callback(Camera::Result::Error); });
1487
        }
1488
        return;
×
1489
    }
1490

1491
    // We get it first so that we have the type of the param value.
1492
    ParamValue value;
×
1493

1494
    if (_camera_definition->is_setting_range(setting_id)) {
×
1495
        // TODO: Get type from minimum.
1496
        std::vector<ParamValue> all_values;
×
1497
        if (!_camera_definition->get_all_options(setting_id, all_values)) {
×
1498
            if (callback) {
×
1499
                LogErr() << "Could not get all options to get type for range param.";
×
1500
                const auto temp_callback = callback;
×
1501
                _system_impl->call_user_callback(
×
1502
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1503
            }
1504
            return;
×
1505
        }
1506

1507
        if (all_values.size() == 0) {
×
1508
            if (callback) {
×
1509
                LogErr() << "Could not get any options to get type for range param.";
×
1510
                const auto temp_callback = callback;
×
1511
                _system_impl->call_user_callback(
×
1512
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1513
            }
1514
            return;
×
1515
        }
1516
        value = all_values[0];
×
1517
        // Now re-use that type.
1518
        // FIXME: this is quite ugly, we should do better than that.
1519
        if (!value.set_as_same_type(option.option_id)) {
×
1520
            if (callback) {
×
1521
                LogErr() << "Could not set option value to given type.";
×
1522
                const auto temp_callback = callback;
×
1523
                _system_impl->call_user_callback(
×
1524
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1525
            }
1526
            return;
×
1527
        }
1528

1529
    } else {
1530
        if (!_camera_definition->get_option_value(setting_id, option.option_id, value)) {
×
1531
            if (callback) {
×
1532
                LogErr() << "Could not get option value.";
×
1533
                const auto temp_callback = callback;
×
1534
                _system_impl->call_user_callback(
×
1535
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1536
            }
1537
            return;
×
1538
        }
1539

1540
        std::vector<ParamValue> possible_values;
×
1541
        _camera_definition->get_possible_options(setting_id, possible_values);
×
1542
        bool allowed = false;
×
1543
        for (const auto& possible_value : possible_values) {
×
1544
            if (value == possible_value) {
×
1545
                allowed = true;
×
1546
            }
1547
        }
1548
        if (!allowed) {
×
1549
            LogErr() << "Setting " << setting_id << "(" << option.option_id << ") not allowed";
×
1550
            if (callback) {
×
1551
                const auto temp_callback = callback;
×
1552
                _system_impl->call_user_callback(
×
1553
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1554
            }
1555
            return;
×
1556
        }
1557
    }
1558

1559
    _system_impl->set_param_async(
×
1560
        setting_id,
1561
        value,
1562
        [this, callback, setting_id, value](MavlinkParameterClient::Result result) {
×
1563
            if (result == MavlinkParameterClient::Result::Success) {
×
1564
                if (!this->_camera_definition) {
×
1565
                    if (callback) {
×
1566
                        const auto temp_callback = callback;
×
1567
                        _system_impl->call_user_callback(
×
1568
                            [temp_callback]() { temp_callback(Camera::Result::Error); });
1569
                    }
1570
                    return;
×
1571
                }
1572

1573
                if (!_camera_definition->set_setting(setting_id, value)) {
×
1574
                    if (callback) {
×
1575
                        const auto temp_callback = callback;
×
1576
                        _system_impl->call_user_callback(
×
1577
                            [temp_callback]() { temp_callback(Camera::Result::Error); });
1578
                    }
1579
                    return;
×
1580
                }
1581

1582
                if (callback) {
×
1583
                    const auto temp_callback = callback;
×
1584
                    _system_impl->call_user_callback(
×
1585
                        [temp_callback]() { temp_callback(Camera::Result::Success); });
1586
                }
1587

1588
                // FIXME: We are already holding the lock when this lambda is run and need to
1589
                //        schedule the refresh_params() for later.
1590
                //        We (ab)use the thread pool for the user callbacks for this.
1591
                _system_impl->call_user_callback([this]() { refresh_params(); });
×
1592
            } else {
1593
                if (callback) {
×
1594
                    const auto temp_callback = callback;
×
1595
                    _system_impl->call_user_callback([temp_callback, result]() {
×
1596
                        temp_callback(camera_result_from_parameter_result(result));
1597
                    });
1598
                }
1599
            }
1600
        },
1601
        this,
1602
        static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA),
×
1603
        true);
1604
}
1605

1606
void CameraImpl::get_setting_async(
×
1607
    Camera::Setting setting, const Camera::GetSettingCallback callback)
1608
{
1609
    get_option_async(
×
1610
        setting.setting_id,
×
1611
        [this, setting, callback](Camera::Result result, const Camera::Option& option) {
×
1612
            Camera::Setting new_setting{};
×
1613
            new_setting.option = option;
×
1614
            if (callback) {
×
1615
                const auto temp_callback = callback;
×
1616
                _system_impl->call_user_callback(
×
1617
                    [temp_callback, result, new_setting]() { temp_callback(result, new_setting); });
1618
            }
1619
        });
×
1620
}
×
1621

1622
std::pair<Camera::Result, Camera::Setting> CameraImpl::get_setting(Camera::Setting setting)
×
1623
{
1624
    auto prom = std::make_shared<std::promise<std::pair<Camera::Result, Camera::Setting>>>();
×
1625
    auto ret = prom->get_future();
×
1626

1627
    get_setting_async(setting, [&prom](Camera::Result result, const Camera::Setting& new_setting) {
×
1628
        prom->set_value(std::make_pair<>(result, new_setting));
×
1629
    });
×
1630

1631
    return ret.get();
×
1632
}
1633

1634
Camera::Result CameraImpl::get_option(const std::string& setting_id, Camera::Option& option)
×
1635
{
1636
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1637
    auto ret = prom->get_future();
×
1638

1639
    get_option_async(
×
1640
        setting_id, [prom, &option](Camera::Result result, const Camera::Option& option_gotten) {
×
1641
            prom->set_value(result);
×
1642
            if (result == Camera::Result::Success) {
×
1643
                option = option_gotten;
×
1644
            }
1645
        });
×
1646

1647
    auto status = ret.wait_for(std::chrono::seconds(1));
×
1648

1649
    if (status == std::future_status::ready) {
×
1650
        return Camera::Result::Success;
×
1651
    } else {
1652
        return Camera::Result::Timeout;
×
1653
    }
1654
}
1655

1656
void CameraImpl::get_option_async(
×
1657
    const std::string& setting_id,
1658
    const std::function<void(Camera::Result, const Camera::Option&)>& callback)
1659
{
1660
    if (!_camera_definition) {
×
1661
        LogWarn() << "Error: no camera defnition available yet.";
×
1662
        if (callback) {
×
1663
            Camera::Option empty_option{};
×
1664
            const auto temp_callback = callback;
×
1665
            _system_impl->call_user_callback([temp_callback, empty_option]() {
×
1666
                temp_callback(Camera::Result::Error, empty_option);
1667
            });
1668
        }
1669
        return;
×
1670
    }
1671

1672
    ParamValue value;
×
1673
    // We should have this cached and don't need to get the param.
1674
    if (_camera_definition->get_setting(setting_id, value)) {
×
1675
        if (callback) {
×
1676
            Camera::Option new_option{};
×
1677
            new_option.option_id = value.get_string();
×
1678
            if (!is_setting_range(setting_id)) {
×
1679
                get_option_str(setting_id, new_option.option_id, new_option.option_description);
×
1680
            }
1681
            const auto temp_callback = callback;
×
1682
            _system_impl->call_user_callback([temp_callback, new_option]() {
×
1683
                temp_callback(Camera::Result::Success, new_option);
1684
            });
1685
        }
1686
    } else {
1687
        // If this still happens, we request the param, but also complain.
1688
        LogWarn() << "Setting '" << setting_id << "' not found.";
×
1689
        if (callback) {
×
1690
            Camera::Option no_option{};
×
1691
            const auto temp_callback = callback;
×
1692
            _system_impl->call_user_callback(
×
1693
                [temp_callback, no_option]() { temp_callback(Camera::Result::Error, no_option); });
1694
        }
1695
    }
1696
}
1697

1698
Camera::CurrentSettingsHandle
1699
CameraImpl::subscribe_current_settings(const Camera::CurrentSettingsCallback& callback)
×
1700
{
1701
    std::unique_lock<std::mutex> lock(_subscribe_current_settings.mutex);
×
1702
    auto handle = _subscribe_current_settings.callbacks.subscribe(callback);
×
1703
    lock.unlock();
×
1704

1705
    notify_current_settings();
×
1706
    return handle;
×
1707
}
1708

1709
void CameraImpl::unsubscribe_current_settings(Camera::CurrentSettingsHandle handle)
×
1710
{
1711
    std::lock_guard<std::mutex> lock(_subscribe_current_settings.mutex);
×
1712
    _subscribe_current_settings.callbacks.unsubscribe(handle);
×
1713
}
×
1714

1715
Camera::PossibleSettingOptionsHandle CameraImpl::subscribe_possible_setting_options(
×
1716
    const Camera::PossibleSettingOptionsCallback& callback)
1717
{
1718
    std::unique_lock<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
1719
    auto handle = _subscribe_possible_setting_options.callbacks.subscribe(callback);
×
1720
    lock.unlock();
×
1721

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

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

1732
void CameraImpl::notify_current_settings()
×
1733
{
1734
    std::lock_guard<std::mutex> lock(_subscribe_current_settings.mutex);
×
1735

1736
    if (_subscribe_current_settings.callbacks.empty()) {
×
1737
        return;
×
1738
    }
1739

1740
    if (!_camera_definition) {
×
1741
        LogErr() << "notify_current_settings has no camera definition";
×
1742
        return;
×
1743
    }
1744

1745
    std::vector<Camera::Setting> current_settings{};
×
1746
    std::vector<std::string> possible_setting_options{};
×
1747
    if (!get_possible_setting_options(possible_setting_options)) {
×
1748
        LogErr() << "Could not get possible settings in current options subscription.";
×
1749
        return;
×
1750
    }
1751

1752
    for (auto& possible_setting : possible_setting_options) {
×
1753
        // use the cache for this, presumably we updated it right before.
1754
        ParamValue value;
×
1755
        if (_camera_definition->get_setting(possible_setting, value)) {
×
1756
            Camera::Setting setting{};
×
1757
            setting.setting_id = possible_setting;
×
1758
            setting.is_range = is_setting_range(possible_setting);
×
1759
            get_setting_str(setting.setting_id, setting.setting_description);
×
1760
            setting.option.option_id = value.get_string();
×
1761
            if (!is_setting_range(possible_setting)) {
×
1762
                get_option_str(
×
1763
                    setting.setting_id,
1764
                    setting.option.option_id,
1765
                    setting.option.option_description);
1766
            }
1767
            current_settings.push_back(setting);
×
1768
        }
1769
    }
1770

1771
    _subscribe_current_settings.callbacks.queue(
×
1772
        current_settings, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1773
}
1774

1775
void CameraImpl::notify_possible_setting_options()
×
1776
{
1777
    std::lock_guard<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
1778

1779
    if (_subscribe_possible_setting_options.callbacks.empty()) {
×
1780
        return;
×
1781
    }
1782

1783
    if (!_camera_definition) {
×
1784
        LogErr() << "notify_possible_setting_options has no camera definition";
×
1785
        return;
×
1786
    }
1787

1788
    auto setting_options = possible_setting_options();
×
1789
    if (setting_options.size() == 0) {
×
1790
        return;
×
1791
    }
1792

1793
    _subscribe_possible_setting_options.callbacks.queue(
×
1794
        setting_options, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1795
}
1796

1797
std::vector<Camera::SettingOptions> CameraImpl::possible_setting_options()
×
1798
{
1799
    std::vector<Camera::SettingOptions> results{};
×
1800

1801
    std::vector<std::string> possible_settings{};
×
1802
    if (!get_possible_setting_options(possible_settings)) {
×
1803
        LogErr() << "Could not get possible settings.";
×
1804
        return results;
×
1805
    }
1806

1807
    for (auto& possible_setting : possible_settings) {
×
1808
        Camera::SettingOptions setting_options{};
×
1809
        setting_options.setting_id = possible_setting;
×
1810
        setting_options.is_range = _camera_definition->is_setting_range(possible_setting);
×
1811
        get_setting_str(setting_options.setting_id, setting_options.setting_description);
×
1812
        get_possible_options(possible_setting, setting_options.options);
×
1813
        results.push_back(setting_options);
×
1814
    }
1815

1816
    return results;
1817
}
1818

1819
void CameraImpl::refresh_params()
×
1820
{
1821
    if (!_camera_definition) {
×
1822
        return;
×
1823
    }
1824

1825
    std::vector<std::pair<std::string, ParamValue>> params;
×
1826
    _camera_definition->get_unknown_params(params);
×
1827
    if (params.size() == 0) {
×
1828
        // We're assuming that we changed one option and this did not cause
1829
        // any other possible settings to change. However, we still would
1830
        // like to notify the current settings with this one change.
1831
        notify_current_settings();
×
1832
        notify_possible_setting_options();
×
1833
        return;
×
1834
    }
1835

1836
    unsigned count = 0;
×
1837
    for (const auto& param : params) {
×
1838
        const std::string& param_name = param.first;
×
1839
        const ParamValue& param_value_type = param.second;
×
1840
        const bool is_last = (count == params.size() - 1);
×
1841
        _system_impl->get_param_async(
×
1842
            param_name,
1843
            param_value_type,
1844
            [param_name, is_last, this](MavlinkParameterClient::Result result, ParamValue value) {
×
1845
                if (result != MavlinkParameterClient::Result::Success) {
×
1846
                    return;
×
1847
                }
1848
                // We need to check again by the time this callback runs
1849
                if (!this->_camera_definition) {
×
1850
                    return;
×
1851
                }
1852

1853
                if (!this->_camera_definition->set_setting(param_name, value)) {
×
1854
                    return;
×
1855
                }
1856

1857
                if (is_last) {
×
1858
                    notify_current_settings();
×
1859
                    notify_possible_setting_options();
×
1860
                }
1861
            },
1862
            this,
1863
            static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA),
×
1864
            true);
1865
        ++count;
×
1866
    }
1867
}
1868

1869
void CameraImpl::invalidate_params()
×
1870
{
1871
    if (!_camera_definition) {
×
1872
        return;
×
1873
    }
1874

1875
    _camera_definition->set_all_params_unknown();
×
1876
}
1877

1878
bool CameraImpl::get_setting_str(const std::string& setting_id, std::string& description)
×
1879
{
1880
    if (!_camera_definition) {
×
1881
        return false;
×
1882
    }
1883

1884
    return _camera_definition->get_setting_str(setting_id, description);
×
1885
}
1886

1887
bool CameraImpl::get_option_str(
×
1888
    const std::string& setting_id, const std::string& option_id, std::string& description)
1889
{
1890
    if (!_camera_definition) {
×
1891
        return false;
×
1892
    }
1893

1894
    return _camera_definition->get_option_str(setting_id, option_id, description);
×
1895
}
1896

1897
void CameraImpl::request_camera_settings()
×
1898
{
1899
    auto command_camera_settings = make_command_request_camera_settings();
×
1900
    _system_impl->send_command_async(command_camera_settings, nullptr);
×
1901
}
×
1902

1903
void CameraImpl::request_flight_information()
×
1904
{
1905
    auto command_flight_information = make_command_request_flight_information();
×
1906
    _system_impl->send_command_async(command_flight_information, nullptr);
×
1907
}
×
1908

1909
void CameraImpl::request_camera_information()
×
1910
{
1911
    auto command_camera_info = make_command_request_camera_info();
×
1912
    _system_impl->send_command_async(command_camera_info, nullptr);
×
1913
}
×
1914

1915
Camera::Result CameraImpl::format_storage()
×
1916
{
1917
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1918
    auto ret = prom->get_future();
×
1919

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

1922
    return ret.get();
×
1923
}
1924

1925
void CameraImpl::format_storage_async(Camera::ResultCallback callback)
×
1926
{
1927
    MavlinkCommandSender::CommandLong cmd_format{};
×
1928

1929
    cmd_format.command = MAV_CMD_STORAGE_FORMAT;
×
1930
    cmd_format.params.maybe_param1 = 1.0f; // storage ID
×
1931
    cmd_format.params.maybe_param2 = 1.0f; // format
×
1932
    cmd_format.params.maybe_param3 = 1.0f; // clear
×
1933
    cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
1934

1935
    _system_impl->send_command_async(
×
1936
        cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
×
1937
            UNUSED(progress);
×
1938

1939
            receive_command_result(result, [this, callback](Camera::Result camera_result) {
×
1940
                if (camera_result == Camera::Result::Success) {
×
1941
                    reset_following_format_storage();
×
1942
                }
1943

1944
                callback(camera_result);
×
1945
            });
×
1946
        });
×
1947
}
×
1948

1949
void CameraImpl::reset_following_format_storage()
×
1950
{
1951
    {
1952
        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
1953
        _status.photo_list.clear();
×
1954
        _status.image_count = 0;
×
1955
        _status.image_count_at_connection = 0;
×
1956
    }
1957
    {
1958
        std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1959
        _capture_info.last_advertised_image_index = -1;
×
1960
        _capture_info.missing_image_retries.clear();
×
1961
    }
1962
}
×
1963

1964
std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>
1965
CameraImpl::list_photos(Camera::PhotosRange photos_range)
×
1966
{
1967
    std::promise<std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>> prom;
×
1968
    auto ret = prom.get_future();
×
1969

1970
    list_photos_async(
×
1971
        photos_range, [&prom](Camera::Result result, std::vector<Camera::CaptureInfo> photo_list) {
×
1972
            prom.set_value(std::make_pair(result, photo_list));
×
1973
        });
×
1974

1975
    return ret.get();
×
1976
}
1977

1978
void CameraImpl::list_photos_async(
×
1979
    Camera::PhotosRange photos_range, const Camera::ListPhotosCallback callback)
1980
{
1981
    if (!callback) {
×
1982
        LogWarn() << "Trying to get a photo list with a null callback, ignoring...";
×
1983
        return;
×
1984
    }
1985

1986
    {
1987
        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
1988

1989
        if (_status.is_fetching_photos) {
×
1990
            _system_impl->call_user_callback([callback]() {
×
1991
                callback(Camera::Result::Busy, std::vector<Camera::CaptureInfo>{});
1992
            });
1993
            return;
×
1994
        } else {
1995
            _status.is_fetching_photos = true;
×
1996
        }
1997

1998
        if (_status.image_count == -1) {
×
1999
            LogErr() << "Cannot list photos: camera status has not been received yet!";
×
2000
            _status.is_fetching_photos = false;
×
2001
            _system_impl->call_user_callback([callback]() {
×
2002
                callback(Camera::Result::Error, std::vector<Camera::CaptureInfo>{});
2003
            });
2004
            return;
×
2005
        }
2006
    }
2007

2008
    const int start_index = [this, photos_range]() {
×
2009
        switch (photos_range) {
×
2010
            case Camera::PhotosRange::SinceConnection:
×
2011
                return _status.image_count_at_connection;
×
2012
            case Camera::PhotosRange::All:
×
2013
            // FALLTHROUGH
2014
            default:
2015
                return 0;
×
2016
        }
2017
    }();
×
2018

2019
    std::thread([this, start_index, callback]() {
×
2020
        std::unique_lock<std::mutex> capture_request_lock(_captured_request_mutex);
×
2021

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

2028
            while (_status.photo_list.find(i) == _status.photo_list.end() &&
×
2029
                   safety_count < safety_count_boundary) {
2030
                safety_count++;
×
2031

2032
                auto request_try_number = 0;
×
2033
                const auto request_try_limit =
×
2034
                    10; // Timeout if the request times out that many times
2035
                auto cv_status = std::cv_status::timeout;
×
2036

2037
                while (cv_status == std::cv_status::timeout) {
×
2038
                    request_try_number++;
×
2039
                    if (request_try_number >= request_try_limit) {
×
2040
                        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2041
                        _status.is_fetching_photos = false;
×
2042
                        _system_impl->call_user_callback([callback]() {
×
2043
                            callback(Camera::Result::Timeout, std::vector<Camera::CaptureInfo>{});
2044
                        });
2045
                        return;
×
2046
                    }
2047

2048
                    _system_impl->send_command_async(
×
2049
                        make_command_request_camera_image_captured(i), nullptr);
2050
                    cv_status = _captured_request_cv.wait_for(
×
2051
                        capture_request_lock, std::chrono::seconds(1));
×
2052
                }
2053
            }
2054

2055
            if (safety_count == safety_count_boundary) {
×
2056
                std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2057
                _status.is_fetching_photos = false;
×
2058
                _system_impl->call_user_callback([callback]() {
×
2059
                    callback(Camera::Result::Error, std::vector<Camera::CaptureInfo>{});
2060
                });
2061
                return;
×
2062
            }
2063
        }
2064

2065
        std::vector<Camera::CaptureInfo> photo_list;
×
2066
        {
2067
            std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2068

2069
            for (auto capture_info : _status.photo_list) {
×
2070
                if (capture_info.first >= start_index) {
×
2071
                    photo_list.push_back(capture_info.second);
×
2072
                }
2073
            }
2074

2075
            _status.is_fetching_photos = false;
×
2076

2077
            const auto temp_callback = callback;
×
2078
            _system_impl->call_user_callback([temp_callback, photo_list]() {
×
2079
                temp_callback(Camera::Result::Success, photo_list);
2080
            });
2081
        }
2082
    }).detach();
×
2083
}
2084

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