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

mavlink / MAVSDK / 11767930807

10 Nov 2024 07:33PM UTC coverage: 38.608% (+0.7%) from 37.921%
11767930807

push

github

web-flow
Merge pull request #2394 from mavlink/pr-consolidate-ci

Consolidate CI

12030 of 31159 relevant lines covered (38.61%)

243.33 hits per line

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

4.3
/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
#include "fs_utils.h"
9

10
#include <algorithm>
11
#include <cmath>
12
#include <filesystem>
13
#include <fstream>
14
#include <functional>
15
#include <sstream>
16

17
namespace mavsdk {
18

19
template class CallbackList<Camera::Mode>;
20
template class CallbackList<std::vector<Camera::Setting>>;
21
template class CallbackList<std::vector<Camera::SettingOptions>>;
22
template class CallbackList<Camera::CaptureInfo>;
23
template class CallbackList<Camera::VideoStreamInfo>;
24
template class CallbackList<Camera::Status>;
25

26
CameraImpl::CameraImpl(System& system) : PluginImplBase(system)
×
27
{
28
    _system_impl->register_plugin(this);
×
29
}
×
30

31
CameraImpl::CameraImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
1✔
32
{
33
    _system_impl->register_plugin(this);
1✔
34
}
1✔
35

36
CameraImpl::~CameraImpl()
2✔
37
{
38
    _system_impl->unregister_plugin(this);
1✔
39
}
2✔
40

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

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

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

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

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

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

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

85
    _check_connection_status_call_every_cookie =
1✔
86
        _system_impl->add_call_every([this]() { check_connection_status(); }, 0.5);
2✔
87

88
    _request_missing_capture_info_cookie =
1✔
89
        _system_impl->add_call_every([this]() { request_missing_capture_info(); }, 0.5);
2✔
90
}
1✔
91

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

103
    {
104
        std::lock_guard<std::mutex> lock(_status.mutex);
1✔
105
        _status.subscription_callbacks.clear();
1✔
106
    }
1✔
107

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

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

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

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

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

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

138
    _camera_found = false;
1✔
139
}
1✔
140

141
Camera::Result CameraImpl::prepare()
×
142
{
143
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
144
    auto ret = prom->get_future();
×
145

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

148
    return ret.get();
×
149
}
×
150

151
void CameraImpl::prepare_async(const Camera::ResultCallback& callback)
×
152
{
153
    auto temp_callback = callback;
×
154

155
    std::lock_guard<std::mutex> lock(_information.mutex);
×
156

157
    if (_camera_definition) {
×
158
        _system_impl->call_user_callback(
×
159
            [temp_callback]() { temp_callback(Camera::Result::Success); });
160
    } else {
161
        _camera_definition_callback = [this, temp_callback](Camera::Result result) {
×
162
            temp_callback(result);
×
163
            _camera_definition_callback = nullptr;
×
164
        };
×
165

166
        if (_has_camera_definition_timed_out) {
×
167
            // Try to download the camera_definition again
168
            _has_camera_definition_timed_out = false;
×
169
            request_camera_information();
×
170
        }
171
    }
172
}
×
173

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

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

194
void CameraImpl::manual_enable()
×
195
{
196
    refresh_params();
×
197

198
    request_status();
×
199
    request_camera_information();
×
200

201
    _camera_information_call_every_cookie =
×
202
        _system_impl->add_call_every([this]() { request_camera_information(); }, 10.0);
×
203

204
    _status.call_every_cookie = _system_impl->add_call_every([this]() { request_status(); }, 5.0);
×
205
}
×
206

207
void CameraImpl::disable()
1✔
208
{
209
    // FIXME: We check for the connection status manually because
210
    // we're not interested in the connection state of the autopilot
211
    // but only the camera.
212
}
1✔
213

214
void CameraImpl::manual_disable()
×
215
{
216
    invalidate_params();
×
217
    _system_impl->remove_call_every(_camera_information_call_every_cookie);
×
218
    _system_impl->remove_call_every(_status.call_every_cookie);
×
219

220
    _camera_found = false;
×
221
}
×
222

223
void CameraImpl::update_component()
×
224
{
225
    uint8_t cmp_id = _camera_id + MAV_COMP_ID_CAMERA;
×
226
    _system_impl->update_component_id_messages_handler(
×
227
        MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, cmp_id, this);
228

229
    _system_impl->update_component_id_messages_handler(
×
230
        MAVLINK_MSG_ID_STORAGE_INFORMATION, cmp_id, this);
231

232
    _system_impl->update_component_id_messages_handler(
×
233
        MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, cmp_id, this);
234

235
    _system_impl->update_component_id_messages_handler(
×
236
        MAVLINK_MSG_ID_CAMERA_SETTINGS, cmp_id, this);
237

238
    _system_impl->update_component_id_messages_handler(
×
239
        MAVLINK_MSG_ID_CAMERA_INFORMATION, cmp_id, this);
240

241
    _system_impl->update_component_id_messages_handler(
×
242
        MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, cmp_id, this);
243

244
    _system_impl->update_component_id_messages_handler(
×
245
        MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, cmp_id, this);
246
}
×
247

248
Camera::Result CameraImpl::select_camera(const size_t id)
×
249
{
250
    static constexpr std::size_t MAX_SUPPORTED_ID = 5;
251

252
    if (id > MAX_SUPPORTED_ID) {
×
253
        return Camera::Result::WrongArgument;
×
254
    }
255

256
    // camera component IDs go from 100 to 105.
257
    _camera_id = id;
×
258

259
    // We should probably reload everything to make sure the
260
    // correct  camera is initialized.
261
    update_component();
×
262
    manual_disable();
×
263
    manual_enable();
×
264

265
    return Camera::Result::Success;
×
266
}
267

268
MavlinkCommandSender::CommandLong
269
CameraImpl::make_command_take_photo(float interval_s, float no_of_photos)
×
270
{
271
    MavlinkCommandSender::CommandLong cmd_take_photo{};
×
272

273
    cmd_take_photo.command = MAV_CMD_IMAGE_START_CAPTURE;
×
274
    cmd_take_photo.params.maybe_param1 = 0.0f; // Reserved, set to 0
×
275
    cmd_take_photo.params.maybe_param2 = interval_s;
×
276
    cmd_take_photo.params.maybe_param3 = no_of_photos;
×
277
    cmd_take_photo.params.maybe_param4 = static_cast<float>(_capture.sequence++);
×
278
    cmd_take_photo.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
279

280
    return cmd_take_photo;
×
281
}
282

283
MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_out()
×
284
{
285
    MavlinkCommandSender::CommandLong cmd{};
×
286
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
287
    cmd.params.maybe_param1 = (float)ZOOM_TYPE_CONTINUOUS;
×
288
    cmd.params.maybe_param2 = -1.f;
×
289
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
290

291
    return cmd;
×
292
}
293

294
MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_in()
×
295
{
296
    MavlinkCommandSender::CommandLong cmd{};
×
297
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
298
    cmd.params.maybe_param1 = (float)ZOOM_TYPE_CONTINUOUS;
×
299
    cmd.params.maybe_param2 = 1.f;
×
300
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
301

302
    return cmd;
×
303
}
304

305
MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_stop()
×
306
{
307
    MavlinkCommandSender::CommandLong cmd{};
×
308
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
309
    cmd.params.maybe_param1 = (float)ZOOM_TYPE_CONTINUOUS;
×
310
    cmd.params.maybe_param2 = 0.f;
×
311
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
312

313
    return cmd;
×
314
}
315

316
MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_range(float range)
×
317
{
318
    // Clip to safe range.
319
    range = std::max(0.f, std::min(range, 100.f));
×
320

321
    MavlinkCommandSender::CommandLong cmd{};
×
322
    cmd.command = MAV_CMD_SET_CAMERA_ZOOM;
×
323
    cmd.params.maybe_param1 = (float)ZOOM_TYPE_RANGE;
×
324
    cmd.params.maybe_param2 = range;
×
325
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
326

327
    return cmd;
×
328
}
329

330
MavlinkCommandSender::CommandLong
331
CameraImpl::make_command_track_point(float point_x, float point_y, float radius)
×
332
{
333
    MavlinkCommandSender::CommandLong cmd{};
×
334
    cmd.command = MAV_CMD_CAMERA_TRACK_POINT;
×
335
    cmd.params.maybe_param1 = (float)point_x;
×
336
    cmd.params.maybe_param2 = (float)point_y;
×
337
    cmd.params.maybe_param3 = (float)radius;
×
338
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
339

340
    return cmd;
×
341
}
342

343
MavlinkCommandSender::CommandLong CameraImpl::make_command_track_rectangle(
×
344
    float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y)
345
{
346
    MavlinkCommandSender::CommandLong cmd{};
×
347
    cmd.command = MAV_CMD_CAMERA_TRACK_RECTANGLE;
×
348
    cmd.params.maybe_param1 = top_left_x;
×
349
    cmd.params.maybe_param2 = top_left_y;
×
350
    cmd.params.maybe_param3 = bottom_right_x;
×
351
    cmd.params.maybe_param4 = bottom_right_y;
×
352
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
353

354
    return cmd;
×
355
}
356
MavlinkCommandSender::CommandLong CameraImpl::make_command_track_stop()
×
357
{
358
    MavlinkCommandSender::CommandLong cmd{};
×
359
    cmd.command = MAV_CMD_CAMERA_STOP_TRACKING;
×
360
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
361

362
    return cmd;
×
363
}
364
MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_in()
×
365
{
366
    MavlinkCommandSender::CommandLong cmd{};
×
367
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
368
    cmd.params.maybe_param1 = (float)FOCUS_TYPE_CONTINUOUS;
×
369
    cmd.params.maybe_param2 = -1.f;
×
370
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
371

372
    return cmd;
×
373
}
374
MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_out()
×
375
{
376
    MavlinkCommandSender::CommandLong cmd{};
×
377
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
378
    cmd.params.maybe_param1 = (float)FOCUS_TYPE_CONTINUOUS;
×
379
    cmd.params.maybe_param2 = 1.f;
×
380
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
381

382
    return cmd;
×
383
}
384
MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_stop()
×
385
{
386
    MavlinkCommandSender::CommandLong cmd{};
×
387
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
388
    cmd.params.maybe_param1 = (float)FOCUS_TYPE_CONTINUOUS;
×
389
    cmd.params.maybe_param2 = 0.f;
×
390
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
391

392
    return cmd;
×
393
}
394
MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_range(float range)
×
395
{
396
    // Clip to safe range.
397
    range = std::max(0.f, std::min(range, 100.f));
×
398

399
    MavlinkCommandSender::CommandLong cmd{};
×
400
    cmd.command = MAV_CMD_SET_CAMERA_FOCUS;
×
401
    cmd.params.maybe_param1 = (float)FOCUS_TYPE_RANGE;
×
402
    cmd.params.maybe_param2 = range;
×
403
    cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
404

405
    return cmd;
×
406
}
407

408
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_photo()
×
409
{
410
    MavlinkCommandSender::CommandLong cmd_stop_photo{};
×
411

412
    cmd_stop_photo.command = MAV_CMD_IMAGE_STOP_CAPTURE;
×
413
    cmd_stop_photo.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
414

415
    return cmd_stop_photo;
×
416
}
417

418
MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video(float capture_status_rate_hz)
×
419
{
420
    MavlinkCommandSender::CommandLong cmd_start_video{};
×
421

422
    cmd_start_video.command = MAV_CMD_VIDEO_START_CAPTURE;
×
423
    cmd_start_video.params.maybe_param1 = 0.f; // Reserved, set to 0
×
424
    cmd_start_video.params.maybe_param2 = capture_status_rate_hz;
×
425
    cmd_start_video.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
426

427
    return cmd_start_video;
×
428
}
429

430
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video()
×
431
{
432
    MavlinkCommandSender::CommandLong cmd_stop_video{};
×
433

434
    cmd_stop_video.command = MAV_CMD_VIDEO_STOP_CAPTURE;
×
435
    cmd_stop_video.params.maybe_param1 = 0.f; // Reserved, set to 0
×
436
    cmd_stop_video.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
437

438
    return cmd_stop_video;
×
439
}
440

441
MavlinkCommandSender::CommandLong CameraImpl::make_command_set_camera_mode(float mavlink_mode)
×
442
{
443
    MavlinkCommandSender::CommandLong cmd_set_camera_mode{};
×
444

445
    cmd_set_camera_mode.command = MAV_CMD_SET_CAMERA_MODE;
×
446
    cmd_set_camera_mode.params.maybe_param1 = 0.0f; // Reserved, set to 0
×
447
    cmd_set_camera_mode.params.maybe_param2 = mavlink_mode;
×
448
    cmd_set_camera_mode.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
449

450
    return cmd_set_camera_mode;
×
451
}
452

453
MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video_streaming(int32_t stream_id)
×
454
{
455
    MavlinkCommandSender::CommandLong cmd_start_video_streaming{};
×
456

457
    cmd_start_video_streaming.command = MAV_CMD_VIDEO_START_STREAMING;
×
458
    cmd_start_video_streaming.params.maybe_param1 = static_cast<float>(stream_id);
×
459
    cmd_start_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
460

461
    return cmd_start_video_streaming;
×
462
}
463

464
MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video_streaming(int32_t stream_id)
×
465
{
466
    MavlinkCommandSender::CommandLong cmd_stop_video_streaming{};
×
467

468
    cmd_stop_video_streaming.command = MAV_CMD_VIDEO_STOP_STREAMING;
×
469
    cmd_stop_video_streaming.params.maybe_param1 = static_cast<float>(stream_id);
×
470
    cmd_stop_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
471

472
    return cmd_stop_video_streaming;
×
473
}
474

475
Camera::Result CameraImpl::take_photo()
×
476
{
477
    // TODO: check whether we are in photo mode.
478

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

481
    // Take 1 photo only with no interval
482
    auto cmd_take_photo = make_command_take_photo(0.f, 1.0f);
×
483

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

487
Camera::Result CameraImpl::zoom_out_start()
×
488
{
489
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
490

491
    auto cmd = make_command_zoom_out();
×
492

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

496
Camera::Result CameraImpl::zoom_in_start()
×
497
{
498
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
499

500
    auto cmd = make_command_zoom_in();
×
501

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

505
Camera::Result CameraImpl::zoom_stop()
×
506
{
507
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
508

509
    auto cmd = make_command_zoom_stop();
×
510

511
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
512
}
×
513

514
Camera::Result CameraImpl::zoom_range(float range)
×
515
{
516
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
517

518
    auto cmd = make_command_zoom_range(range);
×
519

520
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
521
}
×
522

523
Camera::Result CameraImpl::track_point(float point_x, float point_y, float radius)
×
524
{
525
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
526

527
    auto cmd = make_command_track_point(point_x, point_y, radius);
×
528

529
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
530
}
×
531

532
Camera::Result CameraImpl::track_rectangle(
×
533
    float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y)
534
{
535
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
536

537
    auto cmd = make_command_track_rectangle(top_left_x, top_left_y, bottom_right_x, bottom_right_y);
×
538

539
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
540
}
×
541

542
Camera::Result CameraImpl::track_stop()
×
543
{
544
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
545

546
    auto cmd = make_command_track_stop();
×
547

548
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
549
}
×
550

551
Camera::Result CameraImpl::focus_in_start()
×
552
{
553
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
554

555
    auto cmd = make_command_focus_in();
×
556

557
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
558
}
×
559

560
Camera::Result CameraImpl::focus_out_start()
×
561
{
562
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
563

564
    auto cmd = make_command_focus_out();
×
565

566
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
567
}
×
568

569
Camera::Result CameraImpl::focus_stop()
×
570
{
571
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
572

573
    auto cmd = make_command_focus_stop();
×
574

575
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
576
}
×
577

578
Camera::Result CameraImpl::focus_range(float range)
×
579
{
580
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
581

582
    auto cmd = make_command_focus_range(range);
×
583

584
    return camera_result_from_command_result(_system_impl->send_command(cmd));
×
585
}
×
586

587
Camera::Result CameraImpl::start_photo_interval(float interval_s)
×
588
{
589
    if (!interval_valid(interval_s)) {
×
590
        return Camera::Result::WrongArgument;
×
591
    }
592

593
    // TODO: check whether we are in photo mode.
594

595
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
596

597
    auto cmd_take_photo_time_lapse = make_command_take_photo(interval_s, 0.f);
×
598

599
    return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo_time_lapse));
×
600
}
×
601

602
Camera::Result CameraImpl::stop_photo_interval()
×
603
{
604
    auto cmd_stop_photo_interval = make_command_stop_photo();
×
605

606
    return camera_result_from_command_result(_system_impl->send_command(cmd_stop_photo_interval));
×
607
}
608

609
Camera::Result CameraImpl::start_video()
×
610
{
611
    // TODO: check whether video capture is already in progress.
612
    // TODO: check whether we are in video mode.
613

614
    // Capture status rate is not set
615
    auto cmd_start_video = make_command_start_video(0.f);
×
616

617
    return camera_result_from_command_result(_system_impl->send_command(cmd_start_video));
×
618
}
619

620
Camera::Result CameraImpl::stop_video()
×
621
{
622
    auto cmd_stop_video = make_command_stop_video();
×
623

624
    {
625
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
626
        _video_stream_info.data.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning;
×
627
    }
×
628

629
    return camera_result_from_command_result(_system_impl->send_command(cmd_stop_video));
×
630
}
631

632
void CameraImpl::zoom_in_start_async(const Camera::ResultCallback& callback)
×
633
{
634
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
635

636
    auto cmd = make_command_zoom_in();
×
637

638
    _system_impl->send_command_async(
×
639
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
640
            receive_command_result(result, callback);
×
641
        });
×
642
}
×
643

644
void CameraImpl::zoom_out_start_async(const Camera::ResultCallback& callback)
×
645
{
646
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
647

648
    auto cmd = make_command_zoom_out();
×
649

650
    _system_impl->send_command_async(
×
651
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
652
            receive_command_result(result, callback);
×
653
        });
×
654
}
×
655

656
void CameraImpl::zoom_stop_async(const Camera::ResultCallback& callback)
×
657
{
658
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
659

660
    auto cmd = make_command_zoom_stop();
×
661

662
    _system_impl->send_command_async(
×
663
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
664
            receive_command_result(result, callback);
×
665
        });
×
666
}
×
667

668
void CameraImpl::zoom_range_async(float range, const Camera::ResultCallback& callback)
×
669
{
670
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
671

672
    auto cmd = make_command_zoom_range(range);
×
673

674
    _system_impl->send_command_async(
×
675
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
676
            receive_command_result(result, callback);
×
677
        });
×
678
}
×
679

680
void CameraImpl::track_point_async(
×
681
    float point_x, float point_y, float radius, const Camera::ResultCallback& callback)
682
{
683
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
684

685
    auto cmd = make_command_track_point(point_x, point_y, radius);
×
686

687
    _system_impl->send_command_async(
×
688
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
689
            receive_command_result(result, callback);
×
690
        });
×
691
}
×
692

693
void CameraImpl::track_rectangle_async(
×
694
    float top_left_x,
695
    float top_left_y,
696
    float bottom_right_x,
697
    float bottom_right_y,
698
    const Camera::ResultCallback& callback)
699
{
700
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
701

702
    auto cmd = make_command_track_rectangle(top_left_x, top_left_y, bottom_right_x, bottom_right_y);
×
703

704
    _system_impl->send_command_async(
×
705
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
706
            receive_command_result(result, callback);
×
707
        });
×
708
}
×
709

710
void CameraImpl::track_stop_async(const Camera::ResultCallback& callback)
×
711
{
712
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
713

714
    auto cmd = make_command_track_stop();
×
715

716
    _system_impl->send_command_async(
×
717
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
718
            receive_command_result(result, callback);
×
719
        });
×
720
}
×
721

722
void CameraImpl::focus_in_start_async(const Camera::ResultCallback& callback)
×
723
{
724
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
725

726
    auto cmd = make_command_focus_in();
×
727

728
    _system_impl->send_command_async(
×
729
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
730
            receive_command_result(result, callback);
×
731
        });
×
732
}
×
733

734
void CameraImpl::focus_out_start_async(const Camera::ResultCallback& callback)
×
735
{
736
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
737

738
    auto cmd = make_command_focus_out();
×
739

740
    _system_impl->send_command_async(
×
741
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
742
            receive_command_result(result, callback);
×
743
        });
×
744
}
×
745

746
void CameraImpl::focus_stop_async(const Camera::ResultCallback& callback)
×
747
{
748
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
749

750
    auto cmd = make_command_focus_stop();
×
751

752
    _system_impl->send_command_async(
×
753
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
754
            receive_command_result(result, callback);
×
755
        });
×
756
}
×
757

758
void CameraImpl::focus_range_async(float range, const Camera::ResultCallback& callback)
×
759
{
760
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
761

762
    auto cmd = make_command_focus_range(range);
×
763

764
    _system_impl->send_command_async(
×
765
        cmd, [this, callback](MavlinkCommandSender::Result result, float) {
×
766
            receive_command_result(result, callback);
×
767
        });
×
768
}
×
769

770
void CameraImpl::take_photo_async(const Camera::ResultCallback& callback)
×
771
{
772
    // TODO: check whether we are in photo mode.
773

774
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
775

776
    // Take 1 photo only with no interval
777
    auto cmd_take_photo = make_command_take_photo(0.f, 1.0f);
×
778

779
    _system_impl->send_command_async(
×
780
        cmd_take_photo, [this, callback](MavlinkCommandSender::Result result, float) {
×
781
            receive_command_result(result, callback);
×
782
        });
×
783
}
×
784

785
void CameraImpl::start_photo_interval_async(
×
786
    float interval_s, const Camera::ResultCallback& callback)
787
{
788
    if (!interval_valid(interval_s)) {
×
789
        const auto temp_callback = callback;
×
790
        _system_impl->call_user_callback(
×
791
            [temp_callback]() { temp_callback(Camera::Result::WrongArgument); });
792
        return;
×
793
    }
×
794

795
    // TODO: check whether we are in photo mode.
796

797
    std::lock_guard<std::mutex> lock(_capture.mutex);
×
798

799
    auto cmd_take_photo_time_lapse = make_command_take_photo(interval_s, 0.f);
×
800

801
    _system_impl->send_command_async(
×
802
        cmd_take_photo_time_lapse, [this, callback](MavlinkCommandSender::Result result, float) {
×
803
            receive_command_result(result, callback);
×
804
        });
×
805
}
×
806

807
void CameraImpl::stop_photo_interval_async(const Camera::ResultCallback& callback)
×
808
{
809
    auto cmd_stop_photo_interval = make_command_stop_photo();
×
810

811
    _system_impl->send_command_async(
×
812
        cmd_stop_photo_interval, [this, callback](MavlinkCommandSender::Result result, float) {
×
813
            receive_command_result(result, callback);
×
814
        });
×
815
}
×
816

817
void CameraImpl::start_video_async(const Camera::ResultCallback& callback)
×
818
{
819
    // TODO: check whether video capture is already in progress.
820
    // TODO: check whether we are in video mode.
821

822
    // Capture status rate is not set
823
    auto cmd_start_video = make_command_start_video(0.f);
×
824

825
    _system_impl->send_command_async(
×
826
        cmd_start_video, [this, callback](MavlinkCommandSender::Result result, float) {
×
827
            receive_command_result(result, callback);
×
828
        });
×
829
}
×
830

831
void CameraImpl::stop_video_async(const Camera::ResultCallback& callback)
×
832
{
833
    auto cmd_stop_video = make_command_stop_video();
×
834

835
    _system_impl->send_command_async(
×
836
        cmd_stop_video, [this, callback](MavlinkCommandSender::Result result, float) {
×
837
            receive_command_result(result, callback);
×
838
        });
×
839
}
×
840

841
Camera::Information CameraImpl::information() const
×
842
{
843
    std::lock_guard<std::mutex> lock(_information.mutex);
×
844

845
    return _information.data;
×
846
}
×
847

848
Camera::InformationHandle
849
CameraImpl::subscribe_information(const Camera::InformationCallback& callback)
×
850
{
851
    std::lock_guard<std::mutex> lock(_information.mutex);
×
852
    auto handle = _information.subscription_callbacks.subscribe(callback);
×
853

854
    // If there was already a subscription, cancel the call
855
    if (_status.call_every_cookie) {
×
856
        _system_impl->remove_call_every(_status.call_every_cookie);
×
857
    }
858

859
    if (callback) {
×
860
        _system_impl->remove_call_every(_status.call_every_cookie);
×
861
        _status.call_every_cookie =
×
862
            _system_impl->add_call_every([this]() { request_status(); }, 1.0);
×
863
    } else {
864
        _system_impl->remove_call_every(_status.call_every_cookie);
×
865
    }
866

867
    return handle;
×
868
}
×
869

870
void CameraImpl::unsubscribe_information(Camera::InformationHandle handle)
×
871
{
872
    std::lock_guard<std::mutex> lock(_information.mutex);
×
873
    _information.subscription_callbacks.unsubscribe(handle);
×
874
}
×
875

876
Camera::Result CameraImpl::start_video_streaming(int32_t stream_id)
×
877
{
878
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
879

880
    if (_video_stream_info.available &&
×
881
        _video_stream_info.data.status == Camera::VideoStreamInfo::VideoStreamStatus::InProgress) {
×
882
        return Camera::Result::InProgress;
×
883
    }
884

885
    // TODO Check whether we're in video mode
886
    auto command = make_command_start_video_streaming(stream_id);
×
887

888
    auto result = camera_result_from_command_result(_system_impl->send_command(command));
×
889
    // if (result == Camera::Result::Success) {
890
    // Cache video stream info; app may query immediately next.
891
    // TODO: check if we can/should do that.
892
    // auto info = get_video_stream_info();
893
    //}
894
    return result;
×
895
}
×
896

897
Camera::Result CameraImpl::stop_video_streaming(int32_t stream_id)
×
898
{
899
    // TODO I think we need to maintain current state, whether we issued
900
    // video capture request or video streaming request, etc.We shouldn't
901
    // send stop video streaming if we've not started it!
902
    auto command = make_command_stop_video_streaming(stream_id);
×
903

904
    auto result = camera_result_from_command_result(_system_impl->send_command(command));
×
905
    {
906
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
907
        // TODO: check if we can/should do that.
908
        _video_stream_info.data.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning;
×
909
    }
×
910
    return result;
×
911
}
912

913
void CameraImpl::request_video_stream_info()
×
914
{
915
    _system_impl->mavlink_request_message().request(
×
916
        MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, _camera_id + MAV_COMP_ID_CAMERA, nullptr);
×
917
    _system_impl->mavlink_request_message().request(
×
918
        MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, _camera_id + MAV_COMP_ID_CAMERA, nullptr);
×
919
}
×
920

921
Camera::VideoStreamInfo CameraImpl::video_stream_info()
×
922
{
923
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
924

925
    return _video_stream_info.data;
×
926
}
×
927

928
Camera::VideoStreamInfoHandle
929
CameraImpl::subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& callback)
×
930
{
931
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
932

933
    auto handle = _video_stream_info.subscription_callbacks.subscribe(callback);
×
934

935
    if (callback) {
×
936
        _system_impl->remove_call_every(_video_stream_info.call_every_cookie);
×
937
        _video_stream_info.call_every_cookie =
×
938
            _system_impl->add_call_every([this]() { request_video_stream_info(); }, 1.0);
×
939
    } else {
940
        _system_impl->remove_call_every(_video_stream_info.call_every_cookie);
×
941
    }
942

943
    return handle;
×
944
}
×
945

946
void CameraImpl::unsubscribe_video_stream_info(Camera::VideoStreamInfoHandle handle)
×
947
{
948
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
949
    _video_stream_info.subscription_callbacks.unsubscribe(handle);
×
950
}
×
951

952
Camera::Result
953
CameraImpl::camera_result_from_command_result(const MavlinkCommandSender::Result command_result)
×
954
{
955
    switch (command_result) {
×
956
        case MavlinkCommandSender::Result::Success:
×
957
            return Camera::Result::Success;
×
958
        case MavlinkCommandSender::Result::NoSystem:
×
959
            // FALLTHROUGH
960
        case MavlinkCommandSender::Result::ConnectionError:
961
            // FALLTHROUGH
962
        case MavlinkCommandSender::Result::Busy:
963
            return Camera::Result::Error;
×
964
        case MavlinkCommandSender::Result::Failed:
×
965
            return Camera::Result::Error;
×
966
        case MavlinkCommandSender::Result::Denied:
×
967
            // FALLTHROUGH
968
        case MavlinkCommandSender::Result::TemporarilyRejected:
969
            return Camera::Result::Denied;
×
970
        case MavlinkCommandSender::Result::Timeout:
×
971
            return Camera::Result::Timeout;
×
972
        default:
×
973
            return Camera::Result::Unknown;
×
974
    }
975
}
976

977
Camera::Result CameraImpl::camera_result_from_parameter_result(
×
978
    const MavlinkParameterClient::Result parameter_result)
979
{
980
    switch (parameter_result) {
×
981
        case MavlinkParameterClient::Result::Success:
×
982
            return Camera::Result::Success;
×
983
        case MavlinkParameterClient::Result::Timeout:
×
984
            return Camera::Result::Timeout;
×
985
        case MavlinkParameterClient::Result::ConnectionError:
×
986
            return Camera::Result::Error;
×
987
        case MavlinkParameterClient::Result::WrongType:
×
988
            return Camera::Result::WrongArgument;
×
989
        case MavlinkParameterClient::Result::ParamNameTooLong:
×
990
            return Camera::Result::WrongArgument;
×
991
        case MavlinkParameterClient::Result::NotFound:
×
992
            return Camera::Result::WrongArgument;
×
993
        case MavlinkParameterClient::Result::ValueUnsupported:
×
994
            return Camera::Result::WrongArgument;
×
995
        case MavlinkParameterClient::Result::Failed:
×
996
            return Camera::Result::Error;
×
997
        case MavlinkParameterClient::Result::UnknownError:
×
998
            return Camera::Result::Error;
×
999
        default:
×
1000
            return Camera::Result::Unknown;
×
1001
    }
1002
}
1003

1004
Camera::Result CameraImpl::set_mode(const Camera::Mode mode)
×
1005
{
1006
    const float mavlink_mode = to_mavlink_camera_mode(mode);
×
1007
    auto cmd_set_camera_mode = make_command_set_camera_mode(mavlink_mode);
×
1008
    const auto command_result = _system_impl->send_command(cmd_set_camera_mode);
×
1009
    const auto camera_result = camera_result_from_command_result(command_result);
×
1010

1011
    if (camera_result == Camera::Result::Success) {
×
1012
        {
1013
            std::lock_guard<std::mutex> lock(_mode.mutex);
×
1014
            _mode.data = mode;
×
1015
        }
×
1016
        notify_mode();
×
1017
        if (_camera_definition != nullptr) {
×
1018
            save_camera_mode(mavlink_mode);
×
1019
        }
1020
    }
1021

1022
    return camera_result;
×
1023
}
1024

1025
void CameraImpl::save_camera_mode(const float mavlink_camera_mode)
×
1026
{
1027
    if (!std::isfinite(mavlink_camera_mode)) {
×
1028
        LogWarn() << "Can't save NAN as camera mode";
×
1029
        return;
×
1030
    }
1031

1032
    // If there is a camera definition (which is the case if we are
1033
    // in this function, and if CAM_MODE is defined there, then
1034
    // we reuse that type. Otherwise, we hardcode it to `uint32_t`.
1035
    // Note that it could be that the camera definition defines options
1036
    // different than {PHOTO, VIDEO}, in which case the mode received
1037
    // from CAMERA_SETTINGS will be wrong. Not sure if it means that
1038
    // it should be ignored in that case, but that may be tricky to
1039
    // maintain (what if the MAVLink CAMERA_MODE enum evolves?), so
1040
    // I am assuming here that in such a case, CAMERA_SETTINGS is
1041
    // never sent by the camera.
1042
    ParamValue value;
×
1043
    if (_camera_definition->get_setting("CAM_MODE", value)) {
×
1044
        if (value.is<uint8_t>()) {
×
1045
            value.set<uint8_t>(static_cast<uint8_t>(mavlink_camera_mode));
×
1046
        } else if (value.is<int8_t>()) {
×
1047
            value.set<int8_t>(static_cast<int8_t>(mavlink_camera_mode));
×
1048
        } else if (value.is<uint16_t>()) {
×
1049
            value.set<uint16_t>(static_cast<uint16_t>(mavlink_camera_mode));
×
1050
        } else if (value.is<int16_t>()) {
×
1051
            value.set<int16_t>(static_cast<int16_t>(mavlink_camera_mode));
×
1052
        } else if (value.is<uint32_t>()) {
×
1053
            value.set<uint32_t>(static_cast<uint32_t>(mavlink_camera_mode));
×
1054
        } else if (value.is<int32_t>()) {
×
1055
            value.set<int32_t>(static_cast<int32_t>(mavlink_camera_mode));
×
1056
        } else if (value.is<uint64_t>()) {
×
1057
            value.set<uint64_t>(static_cast<uint64_t>(mavlink_camera_mode));
×
1058
        } else if (value.is<int64_t>()) {
×
1059
            value.set<int64_t>(static_cast<int64_t>(mavlink_camera_mode));
×
1060
        } else if (value.is<float>()) {
×
1061
            value.set<float>(static_cast<float>(mavlink_camera_mode));
×
1062
        } else if (value.is<double>()) {
×
1063
            value.set<double>(static_cast<double>(mavlink_camera_mode));
×
1064
        }
1065
    } else {
1066
        value.set<uint32_t>(static_cast<uint32_t>(mavlink_camera_mode));
×
1067
    }
1068

1069
    _camera_definition->set_setting("CAM_MODE", value);
×
1070
    refresh_params();
×
1071
}
×
1072

1073
float CameraImpl::to_mavlink_camera_mode(const Camera::Mode mode) const
×
1074
{
1075
    switch (mode) {
×
1076
        case Camera::Mode::Photo:
×
1077
            return CAMERA_MODE_IMAGE;
×
1078
        case Camera::Mode::Video:
×
1079
            return CAMERA_MODE_VIDEO;
×
1080
        default:
×
1081
        case Camera::Mode::Unknown:
1082
            return NAN;
×
1083
    }
1084
}
1085

1086
void CameraImpl::set_mode_async(const Camera::Mode mode, const Camera::ResultCallback& callback)
×
1087
{
1088
    const auto mavlink_mode = to_mavlink_camera_mode(mode);
×
1089
    auto cmd_set_camera_mode = make_command_set_camera_mode(mavlink_mode);
×
1090

1091
    _system_impl->send_command_async(
×
1092
        cmd_set_camera_mode,
1093
        [this, callback, mode](MavlinkCommandSender::Result result, float progress) {
×
1094
            UNUSED(progress);
×
1095
            receive_set_mode_command_result(result, callback, mode);
×
1096
        });
×
1097
}
×
1098

1099
Camera::Mode CameraImpl::mode()
×
1100
{
1101
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
1102
    return _mode.data;
×
1103
}
×
1104

1105
Camera::ModeHandle CameraImpl::subscribe_mode(const Camera::ModeCallback& callback)
×
1106
{
1107
    std::unique_lock<std::mutex> lock(_mode.mutex);
×
1108
    auto handle = _mode.subscription_callbacks.subscribe(callback);
×
1109
    lock.unlock();
×
1110

1111
    notify_mode();
×
1112

1113
    if (callback) {
×
1114
        _system_impl->remove_call_every(_mode.call_every_cookie);
×
1115
        _mode.call_every_cookie =
×
1116
            _system_impl->add_call_every([this]() { request_camera_settings(); }, 5.0);
×
1117
    } else {
1118
        _system_impl->remove_call_every(_mode.call_every_cookie);
×
1119
    }
1120

1121
    return handle;
×
1122
}
×
1123

1124
void CameraImpl::unsubscribe_mode(Camera::ModeHandle handle)
×
1125
{
1126
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
1127
    _mode.subscription_callbacks.unsubscribe(handle);
×
1128
}
×
1129

1130
bool CameraImpl::interval_valid(float interval_s)
×
1131
{
1132
    // Reject everything faster than 1000 Hz, as well as negative inputs.
1133
    if (interval_s < 0.001f) {
×
1134
        LogWarn() << "Invalid interval input";
×
1135
        return false;
×
1136
    } else {
1137
        return true;
×
1138
    }
1139
}
1140

1141
void CameraImpl::request_status()
×
1142
{
1143
    _system_impl->mavlink_request_message().request(
×
1144
        MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, _camera_id + MAV_COMP_ID_CAMERA, nullptr);
×
1145
    _system_impl->mavlink_request_message().request(
×
1146
        MAVLINK_MSG_ID_STORAGE_INFORMATION, _camera_id + MAV_COMP_ID_CAMERA, nullptr);
×
1147
}
×
1148

1149
Camera::StatusHandle CameraImpl::subscribe_status(const Camera::StatusCallback& callback)
×
1150
{
1151
    std::lock_guard<std::mutex> lock(_status.mutex);
×
1152
    auto handle = _status.subscription_callbacks.subscribe(callback);
×
1153

1154
    return handle;
×
1155
}
×
1156

1157
void CameraImpl::unsubscribe_status(Camera::StatusHandle handle)
×
1158
{
1159
    std::lock_guard<std::mutex> lock(_status.mutex);
×
1160
    _status.subscription_callbacks.unsubscribe(handle);
×
1161
}
×
1162

1163
Camera::Status CameraImpl::status()
×
1164
{
1165
    std::lock_guard<std::mutex> lock(_status.mutex);
×
1166
    return _status.data;
×
1167
}
×
1168

1169
Camera::CaptureInfoHandle
1170
CameraImpl::subscribe_capture_info(const Camera::CaptureInfoCallback& callback)
×
1171
{
1172
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1173
    return _capture_info.callbacks.subscribe(callback);
×
1174
}
×
1175

1176
void CameraImpl::unsubscribe_capture_info(Camera::CaptureInfoHandle handle)
×
1177
{
1178
    std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1179
    _capture_info.callbacks.unsubscribe(handle);
×
1180
}
×
1181

1182
void CameraImpl::process_camera_capture_status(const mavlink_message_t& message)
×
1183
{
1184
    mavlink_camera_capture_status_t camera_capture_status;
×
1185
    mavlink_msg_camera_capture_status_decode(&message, &camera_capture_status);
×
1186

1187
    // If image_count got smaller, consider that the storage was formatted.
1188
    if (camera_capture_status.image_count < _status.image_count) {
×
1189
        LogDebug() << "Seems like storage was formatted, setting state accordingly";
×
1190
        reset_following_format_storage();
×
1191
    }
1192

1193
    {
1194
        std::lock_guard<std::mutex> lock(_status.mutex);
×
1195

1196
        _status.data.video_on = (camera_capture_status.video_status == 1);
×
1197
        _status.data.photo_interval_on =
×
1198
            (camera_capture_status.image_status == 2 || camera_capture_status.image_status == 3);
×
1199
        _status.received_camera_capture_status = true;
×
1200
        _status.data.recording_time_s = float(camera_capture_status.recording_time_ms) / 1e3f;
×
1201

1202
        _status.image_count = camera_capture_status.image_count;
×
1203

1204
        if (_status.image_count_at_connection == -1) {
×
1205
            _status.image_count_at_connection = camera_capture_status.image_count;
×
1206
        }
1207
    }
×
1208

1209
    check_status();
×
1210
}
×
1211

1212
void CameraImpl::process_storage_information(const mavlink_message_t& message)
×
1213
{
1214
    mavlink_storage_information_t storage_information;
×
1215
    mavlink_msg_storage_information_decode(&message, &storage_information);
×
1216

1217
    if (storage_information.total_capacity == 0.0f) {
×
1218
        // Some MAVLink systems happen to send the STORAGE_INFORMATION message
1219
        // to indicate that the camera has a slot for a storage even if there
1220
        // is no way to know anything about that storage (e.g. whether or not
1221
        // there is an sdcard in the slot).
1222
        //
1223
        // We consider that a total capacity of 0 means that this is such a
1224
        // message, and we don't expect MAVSDK users to leverage it, which is
1225
        // why it is ignored.
1226
        return;
×
1227
    }
1228

1229
    {
1230
        std::lock_guard<std::mutex> lock(_status.mutex);
×
1231
        _status.data.storage_status = storage_status_from_mavlink(storage_information.status);
×
1232
        _status.data.available_storage_mib = storage_information.available_capacity;
×
1233
        _status.data.used_storage_mib = storage_information.used_capacity;
×
1234
        _status.data.total_storage_mib = storage_information.total_capacity;
×
1235
        _status.data.storage_id = storage_information.storage_id;
×
1236
        _status.data.storage_type = storage_type_from_mavlink(storage_information.type);
×
1237
        _status.received_storage_information = true;
×
1238
    }
×
1239

1240
    check_status();
×
1241
}
1242

1243
Camera::Status::StorageStatus
1244
CameraImpl::storage_status_from_mavlink(const int storage_status) const
×
1245
{
1246
    switch (storage_status) {
×
1247
        case STORAGE_STATUS_EMPTY:
×
1248
            return Camera::Status::StorageStatus::NotAvailable;
×
1249
        case STORAGE_STATUS_UNFORMATTED:
×
1250
            return Camera::Status::StorageStatus::Unformatted;
×
1251
        case STORAGE_STATUS_READY:
×
1252
            return Camera::Status::StorageStatus::Formatted;
×
1253
            break;
1254
        case STORAGE_STATUS_NOT_SUPPORTED:
×
1255
            return Camera::Status::StorageStatus::NotSupported;
×
1256
        default:
×
1257
            LogErr() << "Unknown storage status received.";
×
1258
            return Camera::Status::StorageStatus::NotSupported;
×
1259
    }
1260
}
1261

1262
Camera::Status::StorageType CameraImpl::storage_type_from_mavlink(const int storage_type) const
×
1263
{
1264
    switch (storage_type) {
×
1265
        default:
×
1266
            LogErr() << "Unknown storage_type enum value: " << storage_type;
×
1267
        // FALLTHROUGH
1268
        case STORAGE_TYPE_UNKNOWN:
×
1269
            return mavsdk::Camera::Status::StorageType::Unknown;
×
1270
        case STORAGE_TYPE_USB_STICK:
×
1271
            return mavsdk::Camera::Status::StorageType::UsbStick;
×
1272
        case STORAGE_TYPE_SD:
×
1273
            return mavsdk::Camera::Status::StorageType::Sd;
×
1274
        case STORAGE_TYPE_MICROSD:
×
1275
            return mavsdk::Camera::Status::StorageType::Microsd;
×
1276
        case STORAGE_TYPE_HD:
×
1277
            return mavsdk::Camera::Status::StorageType::Hd;
×
1278
        case STORAGE_TYPE_OTHER:
×
1279
            return mavsdk::Camera::Status::StorageType::Other;
×
1280
    }
1281
}
1282

1283
void CameraImpl::process_camera_image_captured(const mavlink_message_t& message)
×
1284
{
1285
    mavlink_camera_image_captured_t image_captured;
×
1286
    mavlink_msg_camera_image_captured_decode(&message, &image_captured);
×
1287

1288
    {
1289
        Camera::CaptureInfo capture_info = {};
×
1290
        capture_info.position.latitude_deg = image_captured.lat / 1e7;
×
1291
        capture_info.position.longitude_deg = image_captured.lon / 1e7;
×
1292
        capture_info.position.absolute_altitude_m = image_captured.alt / 1e3f;
×
1293
        capture_info.position.relative_altitude_m = image_captured.relative_alt / 1e3f;
×
1294
        capture_info.time_utc_us = image_captured.time_utc;
×
1295
        capture_info.attitude_quaternion.w = image_captured.q[0];
×
1296
        capture_info.attitude_quaternion.x = image_captured.q[1];
×
1297
        capture_info.attitude_quaternion.y = image_captured.q[2];
×
1298
        capture_info.attitude_quaternion.z = image_captured.q[3];
×
1299
        capture_info.attitude_euler_angle =
1300
            to_euler_angle_from_quaternion(capture_info.attitude_quaternion);
×
1301
        capture_info.file_url = std::string(image_captured.file_url);
×
1302
        capture_info.is_success = (image_captured.capture_result == 1);
×
1303
        capture_info.index = image_captured.image_index;
×
1304

1305
        _status.photo_list.insert(std::make_pair(image_captured.image_index, capture_info));
×
1306

1307
        _captured_request_cv.notify_all();
×
1308

1309
        std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
1310
        // Notify user if a new image has been captured.
1311
        if (_capture_info.last_advertised_image_index < capture_info.index) {
×
1312
            _capture_info.callbacks.queue(
×
1313
                capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1314

1315
            if (_capture_info.last_advertised_image_index != -1) {
×
1316
                // Save captured indices that have been dropped to request later, however, don't
1317
                // do it from the very beginning as there might be many photos from a previous
1318
                // time that we don't want to request.
1319
                for (int i = _capture_info.last_advertised_image_index + 1; i < capture_info.index;
×
1320
                     ++i) {
1321
                    if (_capture_info.missing_image_retries.find(i) ==
×
1322
                        _capture_info.missing_image_retries.end()) {
×
1323
                        _capture_info.missing_image_retries[i] = 0;
×
1324
                    }
1325
                }
1326
            }
1327

1328
            _capture_info.last_advertised_image_index = capture_info.index;
×
1329
        }
1330

1331
        else if (auto it = _capture_info.missing_image_retries.find(capture_info.index);
×
1332
                 it != _capture_info.missing_image_retries.end()) {
×
1333
            _capture_info.callbacks.queue(
×
1334
                capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1335
            _capture_info.missing_image_retries.erase(it);
×
1336
        }
1337
    }
×
1338
}
×
1339

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

1344
    for (auto it = _capture_info.missing_image_retries.begin();
×
1345
         it != _capture_info.missing_image_retries.end();
×
1346
         /* ++it */) {
1347
        if (it->second > 3) {
×
1348
            it = _capture_info.missing_image_retries.erase(it);
×
1349
        } else {
1350
            ++it;
×
1351
        }
1352
    }
1353

1354
    if (!_capture_info.missing_image_retries.empty()) {
×
1355
        auto it_lowest_retries = std::min_element(
×
1356
            _capture_info.missing_image_retries.begin(), _capture_info.missing_image_retries.end());
1357
        _system_impl->mavlink_request_message().request(
×
1358
            MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED,
1359
            _camera_id + MAV_COMP_ID_CAMERA,
×
1360
            nullptr,
1361
            it_lowest_retries->first);
×
1362
        it_lowest_retries->second += 1;
×
1363
    }
1364
}
×
1365

1366
Camera::EulerAngle CameraImpl::to_euler_angle_from_quaternion(Camera::Quaternion quaternion)
×
1367
{
1368
    auto& q = quaternion;
×
1369

1370
    // FIXME: This is duplicated from telemetry/math_conversions.cpp.
1371
    Camera::EulerAngle euler_angle;
×
1372
    euler_angle.roll_deg = to_deg_from_rad(
×
1373
        atan2f(2.0f * (q.w * q.x + q.y * q.z), 1.0f - 2.0f * (q.x * q.x + q.y * q.y)));
×
1374

1375
    euler_angle.pitch_deg = to_deg_from_rad(asinf(2.0f * (q.w * q.y - q.z * q.x)));
×
1376
    euler_angle.yaw_deg = to_deg_from_rad(
×
1377
        atan2f(2.0f * (q.w * q.z + q.x * q.y), 1.0f - 2.0f * (q.y * q.y + q.z * q.z)));
×
1378
    return euler_angle;
×
1379
}
1380

1381
void CameraImpl::process_camera_settings(const mavlink_message_t& message)
×
1382
{
1383
    mavlink_camera_settings_t camera_settings;
×
1384
    mavlink_msg_camera_settings_decode(&message, &camera_settings);
×
1385

1386
    {
1387
        std::lock_guard<std::mutex> lock(_mode.mutex);
×
1388
        _mode.data = to_camera_mode(camera_settings.mode_id);
×
1389
    }
×
1390
    notify_mode();
×
1391

1392
    if (_camera_definition) {
×
1393
        // This "parameter" needs to be manually set.
1394
        save_camera_mode(camera_settings.mode_id);
×
1395
    }
1396
}
×
1397

1398
Camera::Mode CameraImpl::to_camera_mode(const uint8_t mavlink_camera_mode) const
×
1399
{
1400
    switch (mavlink_camera_mode) {
×
1401
        case CAMERA_MODE_IMAGE:
×
1402
            return Camera::Mode::Photo;
×
1403
        case CAMERA_MODE_VIDEO:
×
1404
            return Camera::Mode::Video;
×
1405
        default:
×
1406
            return Camera::Mode::Unknown;
×
1407
    }
1408
}
1409

1410
void CameraImpl::process_camera_information(const mavlink_message_t& message)
×
1411
{
1412
    mavlink_camera_information_t camera_information;
×
1413
    mavlink_msg_camera_information_decode(&message, &camera_information);
×
1414

1415
    // Make sure all strings are zero terminated, so we don't overrun anywhere.
1416
    camera_information.vendor_name[sizeof(camera_information.vendor_name) - 1] = '\0';
×
1417
    camera_information.model_name[sizeof(camera_information.model_name) - 1] = '\0';
×
1418
    camera_information.cam_definition_uri[sizeof(camera_information.cam_definition_uri) - 1] = '\0';
×
1419

1420
    std::lock_guard<std::mutex> lock(_information.mutex);
×
1421

1422
    _information.data.vendor_name = (char*)(camera_information.vendor_name);
×
1423
    _information.data.model_name = (char*)(camera_information.model_name);
×
1424
    _information.data.focal_length_mm = camera_information.focal_length;
×
1425
    _information.data.horizontal_sensor_size_mm = camera_information.sensor_size_h;
×
1426
    _information.data.vertical_sensor_size_mm = camera_information.sensor_size_v;
×
1427
    _information.data.horizontal_resolution_px = camera_information.resolution_h;
×
1428
    _information.data.vertical_resolution_px = camera_information.resolution_v;
×
1429

1430
    _information.subscription_callbacks.queue(
×
1431
        _information.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1432

1433
    if (should_fetch_camera_definition(camera_information.cam_definition_uri)) {
×
1434
        _is_fetching_camera_definition = true;
×
1435

1436
        std::thread([this, camera_information]() {
×
1437
            std::string content{};
×
1438
            const auto result = fetch_camera_definition(camera_information, content);
×
1439

1440
            if (result == Camera::Result::Success) {
×
1441
                LogDebug() << "Successfully loaded camera definition";
×
1442

1443
                if (_camera_definition_callback) {
×
1444
                    _system_impl->call_user_callback(
×
1445
                        [this, result]() { _camera_definition_callback(result); });
1446
                }
1447

1448
                _camera_definition.reset(new CameraDefinition());
×
1449
                _camera_definition->load_string(content);
×
1450
                refresh_params();
×
1451

1452
            } else if (result == Camera::Result::ProtocolUnsupported) {
×
1453
                LogWarn() << "Protocol for " << camera_information.cam_definition_uri
×
1454
                          << " not supported";
×
1455
                if (_camera_definition_callback) {
×
1456
                    _system_impl->call_user_callback(
×
1457
                        [this, result]() { _camera_definition_callback(result); });
1458
                }
1459

1460
            } else {
1461
                LogDebug() << "Failed to fetch camera definition!";
×
1462

1463
                if (++_camera_definition_fetch_count >= 3) {
×
1464
                    LogWarn() << "Giving up fetching the camera definition";
×
1465

1466
                    std::lock_guard<std::mutex> thread_lock(_information.mutex);
×
1467
                    _has_camera_definition_timed_out = true;
×
1468

1469
                    if (_camera_definition_callback) {
×
1470
                        _system_impl->call_user_callback(
×
1471
                            [this, result]() { _camera_definition_callback(result); });
1472
                    }
1473
                }
×
1474
            }
1475

1476
            std::lock_guard<std::mutex> thread_lock(_information.mutex);
×
1477
            _is_fetching_camera_definition = false;
×
1478
        }).detach();
×
1479
    }
1480
}
×
1481

1482
bool CameraImpl::should_fetch_camera_definition(const std::string& uri) const
×
1483
{
1484
    return !uri.empty() && !_camera_definition && !_is_fetching_camera_definition &&
×
1485
           !_has_camera_definition_timed_out;
×
1486
}
1487

1488
bool CameraImpl::starts_with(const std::string& str, const std::string& prefix)
×
1489
{
1490
    return str.compare(0, prefix.size(), prefix) == 0;
×
1491
}
1492

1493
Camera::Result CameraImpl::fetch_camera_definition(
×
1494
    const mavlink_camera_information_t& camera_information, std::string& camera_definition_out)
1495
{
1496
    auto& uri = camera_information.cam_definition_uri;
×
1497

1498
    if (starts_with(uri, "http://") || starts_with(uri, "https://")) {
×
1499
        LogInfo() << "Download file: " << uri << " using cURL...";
×
1500
        auto result = download_definition_file_curl(uri, camera_definition_out);
×
1501
        LogInfo() << "Downloaded file, result " << result;
×
1502
        return result;
×
1503
    } else if (starts_with(uri, "mftp://") || starts_with(uri, "mavlinkftp://")) {
×
1504
        LogInfo() << "Download file: " << uri << " using MAVLink FTP...";
×
1505
        auto result = download_definition_file_mftp(uri, camera_definition_out);
×
1506
        LogInfo() << "Downloaded file, result " << result;
×
1507
        return result;
×
1508
    } else {
1509
        LogErr() << "Unknown protocol for URL: " << uri;
×
1510
        return Camera::Result::ProtocolUnsupported;
×
1511
    }
1512
}
1513

1514
Camera::Result CameraImpl::download_definition_file_curl(
×
1515
    const std::string& uri, std::string& camera_definition_out)
1516
{
1517
#if BUILD_WITHOUT_CURL == 1
1518
    UNUSED(uri);
1519
    UNUSED(camera_definition_out);
1520
    return Camera::Result::ProtocolUnsupported;
1521
#else
1522
    HttpLoader http_loader;
×
1523
    LogInfo() << "Downloading camera definition from: " << uri;
×
1524
    if (!http_loader.download_text_sync(uri, camera_definition_out)) {
×
1525
        LogErr() << "Failed to download camera definition.";
×
1526
        return Camera::Result::Error;
×
1527
    }
1528
#endif
1529

1530
    return Camera::Result::Success;
×
1531
}
×
1532

1533
std::string CameraImpl::get_filename_from_path(const std::string& path)
×
1534
{
1535
    size_t pos = path.find_last_of("/");
×
1536
    if (pos != std::string::npos) {
×
1537
        return path.substr(pos + 1);
×
1538
    }
1539
    return path; // If no directory separator is found, return the whole path as the filename
×
1540
}
1541

1542
std::string CameraImpl::strip_mavlinkftp_prefix(const std::string& str)
×
1543
{
1544
    const std::string prefix1 = "mftp://";
×
1545
    const std::string prefix2 = "mavlinkftp://";
×
1546

1547
    if (str.compare(0, prefix1.size(), prefix1) == 0) {
×
1548
        return str.substr(prefix1.size());
×
1549
    }
1550
    if (str.compare(0, prefix2.size(), prefix2) == 0) {
×
1551
        return str.substr(prefix2.size());
×
1552
    }
1553
    return str; // If no known prefix is found, return the original string
×
1554
}
×
1555

1556
Camera::Result CameraImpl::download_definition_file_mftp(
×
1557
    const std::string& uri, std::string& camera_definition_out)
1558
{
1559
    std::string tmp_download_path;
×
1560
    const auto tmp_option = create_tmp_directory("mavsdk-camera-definition-download");
×
1561
    if (tmp_option) {
×
1562
        tmp_download_path = tmp_option.value().string();
×
1563
    } else {
1564
        tmp_download_path = "./mavsdk-camera-definition-download";
×
1565
        std::error_code err;
×
1566
        std::filesystem::create_directory(tmp_download_path, err);
×
1567
    }
1568

1569
    auto prom = std::promise<MavlinkFtpClient::ClientResult>();
×
1570
    auto fut = prom.get_future();
×
1571

1572
    _system_impl->mavlink_ftp_client().download_async(
×
1573
        strip_mavlinkftp_prefix(uri),
×
1574
        tmp_download_path,
1575
        false,
1576
        [&prom](MavlinkFtpClient::ClientResult client_result, MavlinkFtpClient::ProgressData) {
×
1577
            if (client_result != MavlinkFtpClient::ClientResult::Next) {
×
1578
                prom.set_value(client_result);
×
1579
            }
1580
        },
×
1581
        static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA));
×
1582

1583
    auto result = fut.get();
×
1584

1585
    if (result != MavlinkFtpClient::ClientResult::Success) {
×
1586
        LogErr() << "MAVLink FTP download failed: " << result;
×
1587
        return Camera::Result::Error;
×
1588
    }
1589

1590
    std::filesystem::path tmp_file = std::filesystem::path(tmp_download_path) /
×
1591
                                     std::filesystem::path(get_filename_from_path(uri));
×
1592

1593
    std::ifstream file_stream(tmp_file.string());
×
1594
    if (!file_stream.is_open()) {
×
1595
        LogErr() << "Could not open: " << tmp_file.string();
×
1596
        return Camera::Result::Error;
×
1597
    }
1598
    std::stringstream buffer;
×
1599
    buffer << file_stream.rdbuf();
×
1600
    camera_definition_out = buffer.str();
×
1601
    return Camera::Result::Success;
×
1602
}
×
1603

1604
void CameraImpl::process_video_information(const mavlink_message_t& message)
×
1605
{
1606
    mavlink_video_stream_information_t received_video_info;
×
1607
    mavlink_msg_video_stream_information_decode(&message, &received_video_info);
×
1608

1609
    {
1610
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1611
        // TODO: use stream_id and count
1612
        _video_stream_info.data.status =
×
1613
            (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
×
1614
                 Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1615
                 Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1616
        _video_stream_info.data.spectrum =
×
1617
            (received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
×
1618
                 Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1619
                 Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1620

1621
        auto& video_stream_info = _video_stream_info.data.settings;
×
1622
        video_stream_info.frame_rate_hz = received_video_info.framerate;
×
1623
        video_stream_info.horizontal_resolution_pix = received_video_info.resolution_h;
×
1624
        video_stream_info.vertical_resolution_pix = received_video_info.resolution_v;
×
1625
        video_stream_info.bit_rate_b_s = received_video_info.bitrate;
×
1626
        video_stream_info.rotation_deg = received_video_info.rotation;
×
1627
        video_stream_info.horizontal_fov_deg = static_cast<float>(received_video_info.hfov);
×
1628
        video_stream_info.uri = received_video_info.uri;
×
1629
        _video_stream_info.available = true;
×
1630
    }
×
1631

1632
    notify_video_stream_info();
×
1633
}
×
1634

1635
void CameraImpl::process_video_stream_status(const mavlink_message_t& message)
×
1636
{
1637
    mavlink_video_stream_status_t received_video_stream_status;
×
1638
    mavlink_msg_video_stream_status_decode(&message, &received_video_stream_status);
×
1639
    {
1640
        std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1641
        _video_stream_info.data.status =
×
1642
            (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
×
1643
                 Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
1644
                 Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
1645
        _video_stream_info.data.spectrum =
×
1646
            (received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
×
1647
                 Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
1648
                 Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);
1649

1650
        auto& video_stream_info = _video_stream_info.data.settings;
×
1651
        video_stream_info.frame_rate_hz = received_video_stream_status.framerate;
×
1652
        video_stream_info.horizontal_resolution_pix = received_video_stream_status.resolution_h;
×
1653
        video_stream_info.vertical_resolution_pix = received_video_stream_status.resolution_v;
×
1654
        video_stream_info.bit_rate_b_s = received_video_stream_status.bitrate;
×
1655
        video_stream_info.rotation_deg = received_video_stream_status.rotation;
×
1656
        video_stream_info.horizontal_fov_deg =
×
1657
            static_cast<float>(received_video_stream_status.hfov);
×
1658
        _video_stream_info.available = true;
×
1659
    }
×
1660

1661
    notify_video_stream_info();
×
1662
}
×
1663

1664
void CameraImpl::notify_video_stream_info()
×
1665
{
1666
    std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
×
1667

1668
    _video_stream_info.subscription_callbacks.queue(
×
1669
        _video_stream_info.data,
×
1670
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1671
}
×
1672

1673
void CameraImpl::check_status()
×
1674
{
1675
    std::lock_guard<std::mutex> lock(_status.mutex);
×
1676

1677
    if (_status.received_camera_capture_status && _status.received_storage_information) {
×
1678
        _status.subscription_callbacks.queue(
×
1679
            _status.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1680

1681
        _status.received_camera_capture_status = false;
×
1682
        _status.received_storage_information = false;
×
1683
    }
1684
}
×
1685

1686
void CameraImpl::receive_command_result(
×
1687
    MavlinkCommandSender::Result command_result, const Camera::ResultCallback& callback)
1688
{
1689
    Camera::Result camera_result = camera_result_from_command_result(command_result);
×
1690

1691
    if (callback) {
×
1692
        _system_impl->call_user_callback([callback, camera_result]() { callback(camera_result); });
×
1693
    }
1694
}
×
1695

1696
void CameraImpl::receive_set_mode_command_result(
×
1697
    const MavlinkCommandSender::Result command_result,
1698
    const Camera::ResultCallback callback,
1699
    const Camera::Mode mode)
1700
{
1701
    Camera::Result camera_result = camera_result_from_command_result(command_result);
×
1702

1703
    if (callback) {
×
1704
        const auto temp_callback = callback;
×
1705
        _system_impl->call_user_callback(
×
1706
            [temp_callback, camera_result]() { temp_callback(camera_result); });
1707
    }
×
1708

1709
    if (command_result == MavlinkCommandSender::Result::Success && _camera_definition) {
×
1710
        // This "parameter" needs to be manually set.
1711
        {
1712
            std::lock_guard<std::mutex> lock(_mode.mutex);
×
1713
            _mode.data = mode;
×
1714
        }
×
1715

1716
        const auto mavlink_mode = to_mavlink_camera_mode(mode);
×
1717

1718
        if (std::isnan(mavlink_mode)) {
×
1719
            LogWarn() << "Unknown camera mode";
×
1720
            return;
×
1721
        }
1722

1723
        notify_mode();
×
1724
        save_camera_mode(mavlink_mode);
×
1725
    }
1726
}
1727

1728
void CameraImpl::notify_mode()
×
1729
{
1730
    std::lock_guard<std::mutex> lock(_mode.mutex);
×
1731

1732
    _mode.subscription_callbacks.queue(
×
1733
        _mode.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1734
}
×
1735

1736
bool CameraImpl::get_possible_setting_options(std::vector<std::string>& settings)
×
1737
{
1738
    settings.clear();
×
1739

1740
    if (!_camera_definition) {
×
1741
        LogWarn() << "Error: no camera definition available yet";
×
1742
        return false;
×
1743
    }
1744

1745
    std::unordered_map<std::string, ParamValue> cd_settings{};
×
1746
    _camera_definition->get_possible_settings(cd_settings);
×
1747

1748
    for (const auto& cd_setting : cd_settings) {
×
1749
        if (cd_setting.first == "CAM_MODE") {
×
1750
            // We ignore the mode param.
1751
            continue;
×
1752
        }
1753

1754
        settings.push_back(cd_setting.first);
×
1755
    }
1756

1757
    return settings.size() > 0;
×
1758
}
×
1759

1760
bool CameraImpl::get_possible_options(
×
1761
    const std::string& setting_id, std::vector<Camera::Option>& options)
1762
{
1763
    options.clear();
×
1764

1765
    if (!_camera_definition) {
×
1766
        LogWarn() << "Error: no camera definition available yet";
×
1767
        return false;
×
1768
    }
1769

1770
    std::vector<ParamValue> values;
×
1771
    if (!_camera_definition->get_possible_options(setting_id, values)) {
×
1772
        return false;
×
1773
    }
1774

1775
    for (const auto& value : values) {
×
1776
        std::stringstream ss{};
×
1777
        ss << value;
×
1778
        Camera::Option option{};
×
1779
        option.option_id = ss.str();
×
1780
        if (!is_setting_range(setting_id)) {
×
1781
            get_option_str(setting_id, option.option_id, option.option_description);
×
1782
        }
1783
        options.push_back(option);
×
1784
    }
×
1785

1786
    return options.size() > 0;
×
1787
}
×
1788

1789
bool CameraImpl::is_setting_range(const std::string& setting_id)
×
1790
{
1791
    return _camera_definition->is_setting_range(setting_id);
×
1792
}
1793

1794
Camera::Result CameraImpl::set_setting(Camera::Setting setting)
×
1795
{
1796
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1797
    auto ret = prom->get_future();
×
1798

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

1801
    return ret.get();
×
1802
}
×
1803

1804
void CameraImpl::set_setting_async(Camera::Setting setting, const Camera::ResultCallback callback)
×
1805
{
1806
    set_option_async(setting.setting_id, setting.option, callback);
×
1807
}
×
1808

1809
void CameraImpl::set_option_async(
×
1810
    const std::string& setting_id,
1811
    const Camera::Option& option,
1812
    const Camera::ResultCallback& callback)
1813
{
1814
    if (!_camera_definition) {
×
1815
        LogWarn() << "Error: no camera defnition available yet.";
×
1816
        if (callback) {
×
1817
            const auto temp_callback = callback;
×
1818
            _system_impl->call_user_callback(
×
1819
                [temp_callback]() { temp_callback(Camera::Result::Error); });
1820
        }
×
1821
        return;
×
1822
    }
1823

1824
    // We get it first so that we have the type of the param value.
1825
    ParamValue value;
×
1826

1827
    if (_camera_definition->is_setting_range(setting_id)) {
×
1828
        // TODO: Get type from minimum.
1829
        std::vector<ParamValue> all_values;
×
1830
        if (!_camera_definition->get_all_options(setting_id, all_values)) {
×
1831
            if (callback) {
×
1832
                LogErr() << "Could not get all options to get type for range param.";
×
1833
                const auto temp_callback = callback;
×
1834
                _system_impl->call_user_callback(
×
1835
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1836
            }
×
1837
            return;
×
1838
        }
1839

1840
        if (all_values.size() == 0) {
×
1841
            if (callback) {
×
1842
                LogErr() << "Could not get any options to get type for range param.";
×
1843
                const auto temp_callback = callback;
×
1844
                _system_impl->call_user_callback(
×
1845
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1846
            }
×
1847
            return;
×
1848
        }
1849
        value = all_values[0];
×
1850
        // Now re-use that type.
1851
        // FIXME: this is quite ugly, we should do better than that.
1852
        if (!value.set_as_same_type(option.option_id)) {
×
1853
            if (callback) {
×
1854
                LogErr() << "Could not set option value to given type.";
×
1855
                const auto temp_callback = callback;
×
1856
                _system_impl->call_user_callback(
×
1857
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1858
            }
×
1859
            return;
×
1860
        }
1861

1862
    } else {
×
1863
        if (!_camera_definition->get_option_value(setting_id, option.option_id, value)) {
×
1864
            if (callback) {
×
1865
                LogErr() << "Could not get option value.";
×
1866
                const auto temp_callback = callback;
×
1867
                _system_impl->call_user_callback(
×
1868
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1869
            }
×
1870
            return;
×
1871
        }
1872

1873
        std::vector<ParamValue> possible_values;
×
1874
        _camera_definition->get_possible_options(setting_id, possible_values);
×
1875
        bool allowed = false;
×
1876
        for (const auto& possible_value : possible_values) {
×
1877
            if (value == possible_value) {
×
1878
                allowed = true;
×
1879
            }
1880
        }
1881
        if (!allowed) {
×
1882
            LogErr() << "Setting " << setting_id << "(" << option.option_id << ") not allowed";
×
1883
            if (callback) {
×
1884
                const auto temp_callback = callback;
×
1885
                _system_impl->call_user_callback(
×
1886
                    [temp_callback]() { temp_callback(Camera::Result::Error); });
1887
            }
×
1888
            return;
×
1889
        }
1890
    }
×
1891

1892
    _system_impl->set_param_async(
×
1893
        setting_id,
1894
        value,
1895
        [this, callback, setting_id, value](MavlinkParameterClient::Result result) {
×
1896
            if (result == MavlinkParameterClient::Result::Success) {
×
1897
                if (!this->_camera_definition) {
×
1898
                    if (callback) {
×
1899
                        const auto temp_callback = callback;
×
1900
                        _system_impl->call_user_callback(
×
1901
                            [temp_callback]() { temp_callback(Camera::Result::Error); });
1902
                    }
×
1903
                    return;
×
1904
                }
1905

1906
                if (!_camera_definition->set_setting(setting_id, value)) {
×
1907
                    if (callback) {
×
1908
                        const auto temp_callback = callback;
×
1909
                        _system_impl->call_user_callback(
×
1910
                            [temp_callback]() { temp_callback(Camera::Result::Error); });
1911
                    }
×
1912
                    return;
×
1913
                }
1914

1915
                if (callback) {
×
1916
                    const auto temp_callback = callback;
×
1917
                    _system_impl->call_user_callback(
×
1918
                        [temp_callback]() { temp_callback(Camera::Result::Success); });
1919
                }
×
1920

1921
                // FIXME: We are already holding the lock when this lambda is run and need to
1922
                //        schedule the refresh_params() for later.
1923
                //        We (ab)use the thread pool for the user callbacks for this.
1924
                _system_impl->call_user_callback([this]() { refresh_params(); });
×
1925
            } else {
1926
                if (callback) {
×
1927
                    const auto temp_callback = callback;
×
1928
                    _system_impl->call_user_callback([temp_callback, result]() {
×
1929
                        temp_callback(camera_result_from_parameter_result(result));
1930
                    });
1931
                }
×
1932
            }
1933
        },
1934
        this,
1935
        static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA),
×
1936
        true);
1937
}
×
1938

1939
void CameraImpl::get_setting_async(
×
1940
    Camera::Setting setting, const Camera::GetSettingCallback callback)
1941
{
1942
    get_option_async(
×
1943
        setting.setting_id,
×
1944
        [this, setting, callback](Camera::Result result, const Camera::Option& option) {
×
1945
            Camera::Setting new_setting{};
×
1946
            new_setting.option = option;
×
1947
            if (callback) {
×
1948
                const auto temp_callback = callback;
×
1949
                _system_impl->call_user_callback(
×
1950
                    [temp_callback, result, new_setting]() { temp_callback(result, new_setting); });
1951
            }
×
1952
        });
×
1953
}
×
1954

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

1960
    get_setting_async(setting, [&prom](Camera::Result result, const Camera::Setting& new_setting) {
×
1961
        prom->set_value(std::make_pair<>(result, new_setting));
×
1962
    });
×
1963

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

1967
Camera::Result CameraImpl::get_option(const std::string& setting_id, Camera::Option& option)
×
1968
{
1969
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
1970
    auto ret = prom->get_future();
×
1971

1972
    get_option_async(
×
1973
        setting_id, [prom, &option](Camera::Result result, const Camera::Option& option_gotten) {
×
1974
            prom->set_value(result);
×
1975
            if (result == Camera::Result::Success) {
×
1976
                option = option_gotten;
×
1977
            }
1978
        });
×
1979

1980
    auto status = ret.wait_for(std::chrono::seconds(1));
×
1981

1982
    if (status == std::future_status::ready) {
×
1983
        return Camera::Result::Success;
×
1984
    } else {
1985
        return Camera::Result::Timeout;
×
1986
    }
1987
}
×
1988

1989
void CameraImpl::get_option_async(
×
1990
    const std::string& setting_id,
1991
    const std::function<void(Camera::Result, const Camera::Option&)>& callback)
1992
{
1993
    if (!_camera_definition) {
×
1994
        LogWarn() << "Error: no camera defnition available yet.";
×
1995
        if (callback) {
×
1996
            Camera::Option empty_option{};
×
1997
            const auto temp_callback = callback;
×
1998
            _system_impl->call_user_callback([temp_callback, empty_option]() {
×
1999
                temp_callback(Camera::Result::Error, empty_option);
2000
            });
2001
        }
×
2002
        return;
×
2003
    }
2004

2005
    ParamValue value;
×
2006
    // We should have this cached and don't need to get the param.
2007
    if (_camera_definition->get_setting(setting_id, value)) {
×
2008
        if (callback) {
×
2009
            Camera::Option new_option{};
×
2010
            new_option.option_id = value.get_string();
×
2011
            if (!is_setting_range(setting_id)) {
×
2012
                get_option_str(setting_id, new_option.option_id, new_option.option_description);
×
2013
            }
2014
            const auto temp_callback = callback;
×
2015
            _system_impl->call_user_callback([temp_callback, new_option]() {
×
2016
                temp_callback(Camera::Result::Success, new_option);
2017
            });
2018
        }
×
2019
    } else {
2020
        // If this still happens, we request the param, but also complain.
2021
        LogWarn() << "Setting '" << setting_id << "' not found.";
×
2022
        if (callback) {
×
2023
            Camera::Option no_option{};
×
2024
            const auto temp_callback = callback;
×
2025
            _system_impl->call_user_callback(
×
2026
                [temp_callback, no_option]() { temp_callback(Camera::Result::Error, no_option); });
2027
        }
×
2028
    }
2029
}
×
2030

2031
Camera::CurrentSettingsHandle
2032
CameraImpl::subscribe_current_settings(const Camera::CurrentSettingsCallback& callback)
×
2033
{
2034
    std::unique_lock<std::mutex> lock(_subscribe_current_settings.mutex);
×
2035
    auto handle = _subscribe_current_settings.callbacks.subscribe(callback);
×
2036
    lock.unlock();
×
2037

2038
    notify_current_settings();
×
2039
    return handle;
×
2040
}
×
2041

2042
void CameraImpl::unsubscribe_current_settings(Camera::CurrentSettingsHandle handle)
×
2043
{
2044
    std::lock_guard<std::mutex> lock(_subscribe_current_settings.mutex);
×
2045
    _subscribe_current_settings.callbacks.unsubscribe(handle);
×
2046
}
×
2047

2048
Camera::PossibleSettingOptionsHandle CameraImpl::subscribe_possible_setting_options(
×
2049
    const Camera::PossibleSettingOptionsCallback& callback)
2050
{
2051
    std::unique_lock<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
2052
    auto handle = _subscribe_possible_setting_options.callbacks.subscribe(callback);
×
2053
    lock.unlock();
×
2054

2055
    notify_possible_setting_options();
×
2056
    return handle;
×
2057
}
×
2058

2059
void CameraImpl::unsubscribe_possible_setting_options(Camera::PossibleSettingOptionsHandle handle)
×
2060
{
2061
    std::lock_guard<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
2062
    _subscribe_possible_setting_options.callbacks.unsubscribe(handle);
×
2063
}
×
2064

2065
void CameraImpl::notify_current_settings()
×
2066
{
2067
    std::lock_guard<std::mutex> lock(_subscribe_current_settings.mutex);
×
2068

2069
    if (_subscribe_current_settings.callbacks.empty()) {
×
2070
        return;
×
2071
    }
2072

2073
    if (!_camera_definition) {
×
2074
        LogErr() << "notify_current_settings has no camera definition";
×
2075
        return;
×
2076
    }
2077

2078
    std::vector<Camera::Setting> current_settings{};
×
2079
    std::vector<std::string> possible_setting_options{};
×
2080
    if (!get_possible_setting_options(possible_setting_options)) {
×
2081
        LogErr() << "Could not get possible settings in current options subscription.";
×
2082
        return;
×
2083
    }
2084

2085
    for (auto& possible_setting : possible_setting_options) {
×
2086
        // use the cache for this, presumably we updated it right before.
2087
        ParamValue value;
×
2088
        if (_camera_definition->get_setting(possible_setting, value)) {
×
2089
            Camera::Setting setting{};
×
2090
            setting.setting_id = possible_setting;
×
2091
            setting.is_range = is_setting_range(possible_setting);
×
2092
            get_setting_str(setting.setting_id, setting.setting_description);
×
2093
            setting.option.option_id = value.get_string();
×
2094
            if (!is_setting_range(possible_setting)) {
×
2095
                get_option_str(
×
2096
                    setting.setting_id,
2097
                    setting.option.option_id,
2098
                    setting.option.option_description);
2099
            }
2100
            current_settings.push_back(setting);
×
2101
        }
×
2102
    }
×
2103

2104
    _subscribe_current_settings.callbacks.queue(
×
2105
        current_settings, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
2106
}
×
2107

2108
void CameraImpl::notify_possible_setting_options()
×
2109
{
2110
    std::lock_guard<std::mutex> lock(_subscribe_possible_setting_options.mutex);
×
2111

2112
    if (_subscribe_possible_setting_options.callbacks.empty()) {
×
2113
        return;
×
2114
    }
2115

2116
    if (!_camera_definition) {
×
2117
        LogErr() << "notify_possible_setting_options has no camera definition";
×
2118
        return;
×
2119
    }
2120

2121
    auto setting_options = possible_setting_options();
×
2122
    if (setting_options.size() == 0) {
×
2123
        return;
×
2124
    }
2125

2126
    _subscribe_possible_setting_options.callbacks.queue(
×
2127
        setting_options, [this](const auto& func) { _system_impl->call_user_callback(func); });
×
2128
}
×
2129

2130
std::vector<Camera::SettingOptions> CameraImpl::possible_setting_options()
×
2131
{
2132
    std::vector<Camera::SettingOptions> results{};
×
2133

2134
    std::vector<std::string> possible_settings{};
×
2135
    if (!get_possible_setting_options(possible_settings)) {
×
2136
        LogErr() << "Could not get possible settings.";
×
2137
        return results;
×
2138
    }
2139

2140
    for (auto& possible_setting : possible_settings) {
×
2141
        Camera::SettingOptions setting_options{};
×
2142
        setting_options.setting_id = possible_setting;
×
2143
        setting_options.is_range = _camera_definition->is_setting_range(possible_setting);
×
2144
        get_setting_str(setting_options.setting_id, setting_options.setting_description);
×
2145
        get_possible_options(possible_setting, setting_options.options);
×
2146
        results.push_back(setting_options);
×
2147
    }
×
2148

2149
    return results;
2150
}
×
2151

2152
void CameraImpl::refresh_params()
×
2153
{
2154
    if (!_camera_definition) {
×
2155
        return;
×
2156
    }
2157

2158
    std::vector<std::pair<std::string, ParamValue>> params;
×
2159
    _camera_definition->get_unknown_params(params);
×
2160
    if (params.size() == 0) {
×
2161
        // We're assuming that we changed one option and this did not cause
2162
        // any other possible settings to change. However, we still would
2163
        // like to notify the current settings with this one change.
2164
        notify_current_settings();
×
2165
        notify_possible_setting_options();
×
2166
        return;
×
2167
    }
2168

2169
    unsigned count = 0;
×
2170
    for (const auto& param : params) {
×
2171
        const std::string& param_name = param.first;
×
2172
        const ParamValue& param_value_type = param.second;
×
2173
        const bool is_last = (count == params.size() - 1);
×
2174
        _system_impl->get_param_async(
×
2175
            param_name,
2176
            param_value_type,
2177
            [param_name, is_last, this](MavlinkParameterClient::Result result, ParamValue value) {
×
2178
                if (result != MavlinkParameterClient::Result::Success) {
×
2179
                    return;
×
2180
                }
2181
                // We need to check again by the time this callback runs
2182
                if (!this->_camera_definition) {
×
2183
                    return;
×
2184
                }
2185

2186
                if (!this->_camera_definition->set_setting(param_name, value)) {
×
2187
                    return;
×
2188
                }
2189

2190
                if (is_last) {
×
2191
                    notify_current_settings();
×
2192
                    notify_possible_setting_options();
×
2193
                }
2194
            },
2195
            this,
2196
            static_cast<uint8_t>(_camera_id + MAV_COMP_ID_CAMERA),
×
2197
            true);
2198
        ++count;
×
2199
    }
2200
}
×
2201

2202
void CameraImpl::invalidate_params()
×
2203
{
2204
    if (!_camera_definition) {
×
2205
        return;
×
2206
    }
2207

2208
    _camera_definition->set_all_params_unknown();
×
2209
}
2210

2211
bool CameraImpl::get_setting_str(const std::string& setting_id, std::string& description)
×
2212
{
2213
    if (!_camera_definition) {
×
2214
        return false;
×
2215
    }
2216

2217
    return _camera_definition->get_setting_str(setting_id, description);
×
2218
}
2219

2220
bool CameraImpl::get_option_str(
×
2221
    const std::string& setting_id, const std::string& option_id, std::string& description)
2222
{
2223
    if (!_camera_definition) {
×
2224
        return false;
×
2225
    }
2226

2227
    return _camera_definition->get_option_str(setting_id, option_id, description);
×
2228
}
2229

2230
void CameraImpl::request_camera_settings()
×
2231
{
2232
    _system_impl->mavlink_request_message().request(
×
2233
        MAVLINK_MSG_ID_CAMERA_SETTINGS, _camera_id + MAV_COMP_ID_CAMERA, nullptr);
×
2234
}
×
2235

2236
void CameraImpl::request_camera_information()
×
2237
{
2238
    _system_impl->mavlink_request_message().request(
×
2239
        MAVLINK_MSG_ID_CAMERA_INFORMATION, _camera_id + MAV_COMP_ID_CAMERA, nullptr);
×
2240
}
×
2241

2242
Camera::Result CameraImpl::format_storage(int32_t storage_id)
×
2243
{
2244
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
2245
    auto ret = prom->get_future();
×
2246

2247
    format_storage_async(storage_id, [prom](Camera::Result result) { prom->set_value(result); });
×
2248

2249
    return ret.get();
×
2250
}
×
2251

2252
void CameraImpl::format_storage_async(int32_t storage_id, Camera::ResultCallback callback)
×
2253
{
2254
    MavlinkCommandSender::CommandLong cmd_format{};
×
2255

2256
    cmd_format.command = MAV_CMD_STORAGE_FORMAT;
×
2257
    cmd_format.params.maybe_param1 = static_cast<float>(storage_id); // storage ID
×
2258
    cmd_format.params.maybe_param2 = 1.0f; // format
×
2259
    cmd_format.params.maybe_param3 = 1.0f; // clear
×
2260
    cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
2261

2262
    _system_impl->send_command_async(
×
2263
        cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
×
2264
            UNUSED(progress);
×
2265

2266
            receive_command_result(result, [this, callback](Camera::Result camera_result) {
×
2267
                if (camera_result == Camera::Result::Success) {
×
2268
                    reset_following_format_storage();
×
2269
                }
2270

2271
                callback(camera_result);
×
2272
            });
×
2273
        });
×
2274
}
×
2275

2276
Camera::Result CameraImpl::reset_settings()
×
2277
{
2278
    auto prom = std::make_shared<std::promise<Camera::Result>>();
×
2279
    auto ret = prom->get_future();
×
2280

2281
    reset_settings_async([prom](Camera::Result result) { prom->set_value(result); });
×
2282

2283
    return ret.get();
×
2284
}
×
2285
void CameraImpl::reset_settings_async(const Camera::ResultCallback callback)
×
2286
{
2287
    MavlinkCommandSender::CommandLong cmd_format{};
×
2288

2289
    cmd_format.command = MAV_CMD_RESET_CAMERA_SETTINGS;
×
2290
    cmd_format.params.maybe_param1 = 1.0f; // reset
×
2291
    cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA;
×
2292

2293
    _system_impl->send_command_async(
×
2294
        cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) {
×
2295
            UNUSED(progress);
×
2296

2297
            receive_command_result(result, [this, callback](Camera::Result camera_result) {
×
2298
                callback(camera_result);
×
2299
            });
×
2300
        });
×
2301
}
×
2302

2303
void CameraImpl::reset_following_format_storage()
×
2304
{
2305
    {
2306
        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2307
        _status.photo_list.clear();
×
2308
        _status.image_count = 0;
×
2309
        _status.image_count_at_connection = 0;
×
2310
    }
×
2311
    {
2312
        std::lock_guard<std::mutex> lock(_capture_info.mutex);
×
2313
        _capture_info.last_advertised_image_index = -1;
×
2314
        _capture_info.missing_image_retries.clear();
×
2315
    }
×
2316
}
×
2317

2318
std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>
2319
CameraImpl::list_photos(Camera::PhotosRange photos_range)
×
2320
{
2321
    std::promise<std::pair<Camera::Result, std::vector<Camera::CaptureInfo>>> prom;
×
2322
    auto ret = prom.get_future();
×
2323

2324
    list_photos_async(
×
2325
        photos_range, [&prom](Camera::Result result, std::vector<Camera::CaptureInfo> photo_list) {
×
2326
            prom.set_value(std::make_pair(result, photo_list));
×
2327
        });
×
2328

2329
    return ret.get();
×
2330
}
×
2331

2332
void CameraImpl::list_photos_async(
×
2333
    Camera::PhotosRange photos_range, const Camera::ListPhotosCallback callback)
2334
{
2335
    if (!callback) {
×
2336
        LogWarn() << "Trying to get a photo list with a null callback, ignoring...";
×
2337
        return;
×
2338
    }
2339

2340
    {
2341
        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2342

2343
        if (_status.is_fetching_photos) {
×
2344
            _system_impl->call_user_callback([callback]() {
×
2345
                callback(Camera::Result::Busy, std::vector<Camera::CaptureInfo>{});
2346
            });
2347
            return;
×
2348
        } else {
2349
            _status.is_fetching_photos = true;
×
2350
        }
2351

2352
        if (_status.image_count == -1) {
×
2353
            LogErr() << "Cannot list photos: camera status has not been received yet!";
×
2354
            _status.is_fetching_photos = false;
×
2355
            _system_impl->call_user_callback([callback]() {
×
2356
                callback(Camera::Result::Error, std::vector<Camera::CaptureInfo>{});
2357
            });
2358
            return;
×
2359
        }
2360
    }
×
2361

2362
    const int start_index = [this, photos_range]() {
×
2363
        switch (photos_range) {
×
2364
            case Camera::PhotosRange::SinceConnection:
×
2365
                return _status.image_count_at_connection;
×
2366
            case Camera::PhotosRange::All:
×
2367
            // FALLTHROUGH
2368
            default:
2369
                return 0;
×
2370
        }
2371
    }();
×
2372

2373
    std::thread([this, start_index, callback]() {
×
2374
        std::unique_lock<std::mutex> capture_request_lock(_captured_request_mutex);
×
2375

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

2382
            while (_status.photo_list.find(i) == _status.photo_list.end() &&
×
2383
                   safety_count < safety_count_boundary) {
2384
                safety_count++;
×
2385

2386
                auto request_try_number = 0;
×
2387
                const auto request_try_limit =
×
2388
                    10; // Timeout if the request times out that many times
2389
                auto cv_status = std::cv_status::timeout;
×
2390

2391
                while (cv_status == std::cv_status::timeout) {
×
2392
                    request_try_number++;
×
2393
                    if (request_try_number >= request_try_limit) {
×
2394
                        std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2395
                        _status.is_fetching_photos = false;
×
2396
                        _system_impl->call_user_callback([callback]() {
×
2397
                            callback(Camera::Result::Timeout, std::vector<Camera::CaptureInfo>{});
2398
                        });
2399
                        return;
×
2400
                    }
×
2401

2402
                    _system_impl->mavlink_request_message().request(
×
2403
                        MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED,
2404
                        _camera_id + MAV_COMP_ID_CAMERA,
×
2405
                        nullptr,
2406
                        i);
2407
                    cv_status = _captured_request_cv.wait_for(
×
2408
                        capture_request_lock, std::chrono::seconds(1));
×
2409
                }
2410
            }
2411

2412
            if (safety_count == safety_count_boundary) {
×
2413
                std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2414
                _status.is_fetching_photos = false;
×
2415
                _system_impl->call_user_callback([callback]() {
×
2416
                    callback(Camera::Result::Error, std::vector<Camera::CaptureInfo>{});
2417
                });
2418
                return;
×
2419
            }
×
2420
        }
2421

2422
        std::vector<Camera::CaptureInfo> photo_list;
×
2423
        {
2424
            std::lock_guard<std::mutex> status_lock(_status.mutex);
×
2425

2426
            for (auto capture_info : _status.photo_list) {
×
2427
                if (capture_info.first >= start_index) {
×
2428
                    photo_list.push_back(capture_info.second);
×
2429
                }
2430
            }
×
2431

2432
            _status.is_fetching_photos = false;
×
2433

2434
            const auto temp_callback = callback;
×
2435
            _system_impl->call_user_callback([temp_callback, photo_list]() {
×
2436
                temp_callback(Camera::Result::Success, photo_list);
2437
            });
2438
        }
×
2439
    }).detach();
×
2440
}
2441

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

© 2025 Coveralls, Inc