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

mavlink / MAVSDK / 4899817366

pending completion
4899817366

Pull #1772

github

GitHub
Merge c0bb90862 into e4e9c71dd
Pull Request #1772: Refactor MAVLinkParameters into client and server classes

2192 of 2192 new or added lines in 34 files covered. (100.0%)

7708 of 24812 relevant lines covered (31.07%)

19.96 hits per line

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

10.13
/src/mavsdk/plugins/camera_server/camera_server_impl.cpp
1
#include "camera_server_impl.h"
2
#include "callback_list.tpp"
3

4
#include <thread> // FIXME: remove me
5

6
namespace mavsdk {
7

8
template class CallbackList<int32_t>;
9

10
CameraServerImpl::CameraServerImpl(std::shared_ptr<ServerComponent> server_component) :
1✔
11
    ServerPluginImplBase(server_component)
1✔
12
{
13
    _server_component_impl->register_plugin(this);
1✔
14
}
1✔
15

16
CameraServerImpl::~CameraServerImpl()
1✔
17
{
18
    _server_component_impl->unregister_plugin(this);
1✔
19
}
1✔
20

21
void CameraServerImpl::init()
1✔
22
{
23
    _server_component_impl->register_mavlink_command_handler(
1✔
24
        MAV_CMD_REQUEST_CAMERA_INFORMATION,
25
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
26
            return process_camera_information_request(command);
×
27
        },
28
        this);
29
    _server_component_impl->register_mavlink_command_handler(
1✔
30
        MAV_CMD_REQUEST_CAMERA_SETTINGS,
31
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
32
            return process_camera_settings_request(command);
×
33
        },
34
        this);
35
    _server_component_impl->register_mavlink_command_handler(
1✔
36
        MAV_CMD_REQUEST_STORAGE_INFORMATION,
37
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
38
            return process_storage_information_request(command);
×
39
        },
40
        this);
41
    _server_component_impl->register_mavlink_command_handler(
1✔
42
        MAV_CMD_STORAGE_FORMAT,
43
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
44
            return process_storage_format(command);
×
45
        },
46
        this);
47
    _server_component_impl->register_mavlink_command_handler(
1✔
48
        MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS,
49
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
50
            return process_camera_capture_status_request(command);
×
51
        },
52
        this);
53
    _server_component_impl->register_mavlink_command_handler(
1✔
54
        MAV_CMD_RESET_CAMERA_SETTINGS,
55
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
56
            return process_reset_camera_settings(command);
×
57
        },
58
        this);
59
    _server_component_impl->register_mavlink_command_handler(
1✔
60
        MAV_CMD_SET_CAMERA_MODE,
61
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
62
            return process_set_camera_mode(command);
×
63
        },
64
        this);
65
    _server_component_impl->register_mavlink_command_handler(
1✔
66
        MAV_CMD_SET_CAMERA_ZOOM,
67
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
68
            return process_set_camera_zoom(command);
×
69
        },
70
        this);
71
    _server_component_impl->register_mavlink_command_handler(
1✔
72
        MAV_CMD_SET_CAMERA_FOCUS,
73
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
74
            return process_set_camera_focus(command);
×
75
        },
76
        this);
77
    _server_component_impl->register_mavlink_command_handler(
1✔
78
        MAV_CMD_SET_STORAGE_USAGE,
79
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
80
            return process_set_storage_usage(command);
×
81
        },
82
        this);
83
    _server_component_impl->register_mavlink_command_handler(
1✔
84
        MAV_CMD_IMAGE_START_CAPTURE,
85
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
86
            return process_image_start_capture(command);
×
87
        },
88
        this);
89
    _server_component_impl->register_mavlink_command_handler(
1✔
90
        MAV_CMD_IMAGE_STOP_CAPTURE,
91
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
92
            return process_image_stop_capture(command);
×
93
        },
94
        this);
95
    _server_component_impl->register_mavlink_command_handler(
1✔
96
        MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE,
97
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
98
            return process_camera_image_capture_request(command);
×
99
        },
100
        this);
101
    _server_component_impl->register_mavlink_command_handler(
1✔
102
        MAV_CMD_VIDEO_START_CAPTURE,
103
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
104
            return process_video_start_capture(command);
×
105
        },
106
        this);
107
    _server_component_impl->register_mavlink_command_handler(
1✔
108
        MAV_CMD_VIDEO_STOP_CAPTURE,
109
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
110
            return process_video_stop_capture(command);
×
111
        },
112
        this);
113
    _server_component_impl->register_mavlink_command_handler(
1✔
114
        MAV_CMD_VIDEO_START_STREAMING,
115
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
116
            return process_video_start_streaming(command);
×
117
        },
118
        this);
119
    _server_component_impl->register_mavlink_command_handler(
1✔
120
        MAV_CMD_VIDEO_STOP_STREAMING,
121
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
122
            return process_video_stop_streaming(command);
×
123
        },
124
        this);
125
    _server_component_impl->register_mavlink_command_handler(
1✔
126
        MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION,
127
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
128
            return process_video_stream_information_request(command);
×
129
        },
130
        this);
131
    _server_component_impl->register_mavlink_command_handler(
1✔
132
        MAV_CMD_REQUEST_VIDEO_STREAM_STATUS,
133
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
134
            return process_video_stream_status_request(command);
×
135
        },
136
        this);
137
}
1✔
138

139
void CameraServerImpl::deinit()
1✔
140
{
141
    stop_image_capture_interval();
1✔
142
    _server_component_impl->unregister_all_mavlink_command_handlers(this);
1✔
143
}
1✔
144

145
bool CameraServerImpl::parse_version_string(const std::string& version_str)
×
146
{
147
    uint32_t unused;
×
148

149
    return parse_version_string(version_str, unused);
×
150
}
151

152
bool CameraServerImpl::parse_version_string(const std::string& version_str, uint32_t& version)
×
153
{
154
    // empty string means no version
155
    if (version_str.empty()) {
×
156
        version = 0;
×
157

158
        return true;
×
159
    }
160

161
    uint8_t major{}, minor{}, patch{}, dev{};
×
162

163
    auto ret = sscanf(version_str.c_str(), "%hhu.%hhu.%hhu.%hhu", &major, &minor, &patch, &dev);
×
164

165
    if (ret == EOF) {
×
166
        return false;
×
167
    }
168

169
    // pack version according to MAVLINK spec
170
    version = dev << 24 | patch << 16 | minor << 8 | major;
×
171

172
    return true;
×
173
}
174

175
CameraServer::Result CameraServerImpl::set_information(CameraServer::Information information)
×
176
{
177
    if (!parse_version_string(information.firmware_version)) {
×
178
        LogDebug() << "incorrectly formatted firmware version string: "
×
179
                   << information.firmware_version;
×
180
        return CameraServer::Result::WrongArgument;
×
181
    }
182

183
    // TODO: validate information.definition_file_uri
184

185
    _is_information_set = true;
×
186
    _information = information;
×
187

188
    return CameraServer::Result::Success;
×
189
}
190

191
CameraServer::Result CameraServerImpl::set_in_progress(bool in_progress)
×
192
{
193
    _is_image_capture_in_progress = in_progress;
×
194
    return CameraServer::Result::Success;
×
195
}
196

197
CameraServer::TakePhotoHandle
198
CameraServerImpl::subscribe_take_photo(const CameraServer::TakePhotoCallback& callback)
1✔
199
{
200
    return _take_photo_callbacks.subscribe(callback);
1✔
201
}
202

203
void CameraServerImpl::unsubscribe_take_photo(CameraServer::TakePhotoHandle handle)
×
204
{
205
    _take_photo_callbacks.unsubscribe(handle);
×
206
}
×
207

208
CameraServer::Result CameraServerImpl::respond_take_photo(
×
209
    CameraServer::TakePhotoFeedback take_photo_feedback, CameraServer::CaptureInfo capture_info)
210
{
211
    // If capture_info.index == INT32_MIN, it means this was an interval
212
    // capture rather than a single image capture.
213
    if (capture_info.index != INT32_MIN) {
×
214
        // We expect each capture to be the next sequential number.
215
        // If _image_capture_count == 0, we ignore since it means that this is
216
        // the first photo since the plugin was initialized.
217
        if (_image_capture_count != 0 && capture_info.index != _image_capture_count + 1) {
×
218
            LogErr() << "unexpected image index, expecting " << +(_image_capture_count + 1)
×
219
                     << " but was " << +capture_info.index;
×
220
        }
221

222
        _image_capture_count = capture_info.index;
×
223
    }
224

225
    switch (take_photo_feedback) {
×
226
        default:
×
227
            // Fallthrough
228
        case CameraServer::TakePhotoFeedback::Unknown:
229
            return CameraServer::Result::Error;
×
230
        case CameraServer::TakePhotoFeedback::Ok: {
×
231
            // Check for error above
232
            auto ack_msg = _server_component_impl->make_command_ack_message(
×
233
                _last_take_photo_command, MAV_RESULT_ACCEPTED);
×
234
            _server_component_impl->send_message(ack_msg);
×
235
            // Only break and send the captured below.
236
            break;
×
237
        }
238
        case CameraServer::TakePhotoFeedback::Busy: {
×
239
            auto ack_msg = _server_component_impl->make_command_ack_message(
×
240
                _last_take_photo_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
241
            _server_component_impl->send_message(ack_msg);
×
242
            return CameraServer::Result::Success;
×
243
        }
244
        case CameraServer::TakePhotoFeedback::Failed: {
×
245
            auto ack_msg = _server_component_impl->make_command_ack_message(
×
246
                _last_take_photo_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
247
            _server_component_impl->send_message(ack_msg);
×
248
            return CameraServer::Result::Success;
×
249
        }
250
    }
251

252
    // REVISIT: Should we cache all CaptureInfo in memory for single image
253
    // captures so that we can respond to requests for lost CAMERA_IMAGE_CAPTURED
254
    // messages without calling back to user code?
255

256
    static const uint8_t camera_id = 0; // deprecated unused field
257

258
    const float attitude_quaternion[] = {
×
259
        capture_info.attitude_quaternion.w,
×
260
        capture_info.attitude_quaternion.x,
×
261
        capture_info.attitude_quaternion.y,
×
262
        capture_info.attitude_quaternion.z,
×
263
    };
×
264

265
    // There needs to be enough data to be copied mavlink internal.
266
    capture_info.file_url.resize(205);
×
267

268
    mavlink_message_t msg{};
×
269
    mavlink_msg_camera_image_captured_pack(
×
270
        _server_component_impl->get_own_system_id(),
×
271
        _server_component_impl->get_own_component_id(),
×
272
        &msg,
273
        static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
274
        capture_info.time_utc_us,
275
        camera_id,
276
        static_cast<int32_t>(capture_info.position.latitude_deg * 1e7),
×
277
        static_cast<int32_t>(capture_info.position.longitude_deg * 1e7),
×
278
        static_cast<int32_t>(capture_info.position.absolute_altitude_m * 1e3f),
×
279
        static_cast<int32_t>(capture_info.position.relative_altitude_m * 1e3f),
×
280
        attitude_quaternion,
281
        capture_info.index,
282
        capture_info.is_success,
×
283
        capture_info.file_url.c_str());
284

285
    // TODO: this should be a broadcast message
286
    _server_component_impl->send_message(msg);
×
287
    LogDebug() << "sent camera image captured msg - index: " << +capture_info.index;
×
288

289
    return CameraServer::Result::Success;
×
290
}
291

292
/**
293
 * Starts capturing images with the given interval.
294
 * @param [in]  interval_s      The interval between captures in seconds.
295
 * @param [in]  count           The number of images to capture or 0 for "forever".
296
 * @param [in]  index           The index/sequence number pass to the user callback (always
297
 *                              @c INT32_MIN).
298
 */
299
void CameraServerImpl::start_image_capture_interval(float interval_s, int32_t count, int32_t index)
×
300
{
301
    // If count == 0, it means capture "forever" until a stop command is received.
302
    auto remaining = std::make_shared<int32_t>(count == 0 ? INT32_MAX : count);
×
303

304
    _server_component_impl->add_call_every(
×
305
        [this, remaining, index]() {
×
306
            LogDebug() << "capture image timer triggered";
×
307

308
            if (!_take_photo_callbacks.empty()) {
×
309
                _take_photo_callbacks(index);
×
310
                (*remaining)--;
×
311
            }
312

313
            if (*remaining == 0) {
×
314
                stop_image_capture_interval();
×
315
            }
316
        },
×
317
        interval_s,
318
        &_image_capture_timer_cookie);
319

320
    _is_image_capture_interval_set = true;
×
321
    _image_capture_timer_interval_s = interval_s;
×
322
}
×
323

324
/**
325
 * Stops any pending image capture interval timer.
326
 */
327
void CameraServerImpl::stop_image_capture_interval()
1✔
328
{
329
    if (_image_capture_timer_cookie) {
1✔
330
        _server_component_impl->remove_call_every(_image_capture_timer_cookie);
×
331
    }
332

333
    _image_capture_timer_cookie = nullptr;
1✔
334
    _is_image_capture_interval_set = false;
1✔
335
    _image_capture_timer_interval_s = 0;
1✔
336
}
1✔
337

338
std::optional<mavlink_message_t> CameraServerImpl::process_camera_information_request(
×
339
    const MavlinkCommandReceiver::CommandLong& command)
340
{
341
    auto capabilities = static_cast<bool>(command.params.param1);
×
342

343
    if (!capabilities) {
×
344
        LogDebug() << "early info return";
×
345
        return _server_component_impl->make_command_ack_message(
×
346
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
347
    }
348

349
    if (!_is_information_set) {
×
350
        return _server_component_impl->make_command_ack_message(
×
351
            command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED);
×
352
    }
353

354
    // ack needs to be sent before camera information message
355
    auto ack_msg =
×
356
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
357
    _server_component_impl->send_message(ack_msg);
×
358
    LogDebug() << "sent info ack";
×
359

360
    // FIXME: why is this needed to prevent dropping messages?
361
    std::this_thread::sleep_for(std::chrono::milliseconds(100));
×
362

363
    // It is safe to ignore the return value of parse_version_string() here
364
    // since the string was already validated in set_information().
365
    uint32_t firmware_version;
×
366
    parse_version_string(_information.firmware_version, firmware_version);
×
367

368
    // capability flags are determined by subscriptions
369
    uint32_t capability_flags{};
×
370

371
    if (!_take_photo_callbacks.empty()) {
×
372
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE;
×
373
    }
374

375
    mavlink_message_t msg{};
×
376
    mavlink_msg_camera_information_pack(
×
377
        _server_component_impl->get_own_system_id(),
×
378
        _server_component_impl->get_own_component_id(),
×
379
        &msg,
380
        static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
381
        reinterpret_cast<const uint8_t*>(_information.vendor_name.c_str()),
×
382
        reinterpret_cast<const uint8_t*>(_information.model_name.c_str()),
×
383
        firmware_version,
384
        _information.focal_length_mm,
385
        _information.horizontal_sensor_size_mm,
386
        _information.vertical_sensor_size_mm,
387
        _information.horizontal_resolution_px,
×
388
        _information.vertical_resolution_px,
×
389
        _information.lens_id,
×
390
        capability_flags,
391
        _information.definition_file_version,
×
392
        _information.definition_file_uri.c_str());
393

394
    _server_component_impl->send_message(msg);
×
395
    LogDebug() << "sent info msg";
×
396

397
    // ack was already sent
398
    return std::nullopt;
×
399
}
400

401
std::optional<mavlink_message_t> CameraServerImpl::process_camera_settings_request(
×
402
    const MavlinkCommandReceiver::CommandLong& command)
403
{
404
    auto settings = static_cast<bool>(command.params.param1);
×
405

406
    if (!settings) {
×
407
        LogDebug() << "early settings return";
×
408
        return _server_component_impl->make_command_ack_message(
×
409
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
410
    }
411

412
    // ack needs to be sent before camera information message
413
    auto ack_msg =
×
414
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
415
    _server_component_impl->send_message(ack_msg);
×
416
    LogDebug() << "sent settings ack";
×
417

418
    // FIXME: why is this needed to prevent dropping messages?
419
    std::this_thread::sleep_for(std::chrono::milliseconds(100));
×
420

421
    // unsupported
422
    const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE;
×
423
    const float zoom_level = 0;
×
424
    const float focus_level = 0;
×
425

426
    mavlink_message_t msg{};
×
427
    mavlink_msg_camera_settings_pack(
×
428
        _server_component_impl->get_own_system_id(),
×
429
        _server_component_impl->get_own_component_id(),
×
430
        &msg,
431
        static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
432
        mode_id,
433
        zoom_level,
434
        focus_level);
435

436
    _server_component_impl->send_message(msg);
×
437
    LogDebug() << "sent settings msg";
×
438

439
    // ack was already sent
440
    return std::nullopt;
×
441
}
442

443
std::optional<mavlink_message_t> CameraServerImpl::process_storage_information_request(
×
444
    const MavlinkCommandReceiver::CommandLong& command)
445
{
446
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
447
    auto information = static_cast<bool>(command.params.param2);
×
448

449
    if (!information) {
×
450
        LogDebug() << "early storage return";
×
451
        return _server_component_impl->make_command_ack_message(
×
452
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
453
    }
454

455
    // ack needs to be sent before camera information message
456
    auto ack_msg =
×
457
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
458
    _server_component_impl->send_message(ack_msg);
×
459
    LogDebug() << "sent storage ack";
×
460

461
    // FIXME: why is this needed to prevent dropping messages?
462
    std::this_thread::sleep_for(std::chrono::milliseconds(100));
×
463

464
    // unsupported
465
    const uint8_t storage_count = 0;
×
466
    const auto status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
467
    const float total_capacity = 0;
×
468
    const float used_capacity = 0;
×
469
    const float available_capacity = 0;
×
470
    const float read_speed = 0;
×
471
    const float write_speed = 0;
×
472
    const uint8_t type = STORAGE_TYPE::STORAGE_TYPE_UNKNOWN;
×
473
    std::string name("");
×
474
    // This needs to be long enough, otherwise the memcpy in mavlink overflows.
475
    name.resize(32);
×
476
    const uint8_t storage_usage = 0;
×
477

478
    mavlink_message_t msg{};
×
479
    mavlink_msg_storage_information_pack(
×
480
        _server_component_impl->get_own_system_id(),
×
481
        _server_component_impl->get_own_component_id(),
×
482
        &msg,
483
        static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
484
        storage_id,
485
        storage_count,
486
        status,
487
        total_capacity,
488
        used_capacity,
489
        available_capacity,
490
        read_speed,
491
        write_speed,
492
        type,
493
        name.data(),
×
494
        storage_usage);
495

496
    _server_component_impl->send_message(msg);
×
497
    LogDebug() << "sent storage msg";
×
498

499
    // ack was already sent
500
    return std::nullopt;
×
501
}
502

503
std::optional<mavlink_message_t>
504
CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLong& command)
×
505
{
506
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
507
    auto format = static_cast<bool>(command.params.param2);
×
508
    auto reset_image_log = static_cast<bool>(command.params.param3);
×
509

510
    UNUSED(storage_id);
×
511
    UNUSED(format);
×
512
    UNUSED(reset_image_log);
×
513

514
    LogDebug() << "unsupported storage format request";
×
515

516
    return _server_component_impl->make_command_ack_message(
×
517
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
518
}
519

520
std::optional<mavlink_message_t> CameraServerImpl::process_camera_capture_status_request(
×
521
    const MavlinkCommandReceiver::CommandLong& command)
522
{
523
    auto capture_status = static_cast<bool>(command.params.param1);
×
524

525
    if (!capture_status) {
×
526
        return _server_component_impl->make_command_ack_message(
×
527
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
528
    }
529

530
    // ack needs to be sent before camera information message
531
    auto ack_msg =
×
532
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
533
    _server_component_impl->send_message(ack_msg);
×
534

535
    // FIXME: why is this needed to prevent dropping messages?
536
    std::this_thread::sleep_for(std::chrono::milliseconds(100));
×
537

538
    uint8_t image_status{};
×
539

540
    if (_is_image_capture_in_progress) {
×
541
        image_status |= StatusFlags::IN_PROGRESS;
×
542
    }
543

544
    if (_is_image_capture_interval_set) {
×
545
        image_status |= StatusFlags::INTERVAL_SET;
×
546
    }
547

548
    // unsupported
549
    const uint8_t video_status = 0;
×
550
    const uint32_t recording_time_ms = 0;
×
551
    const float available_capacity = 0;
×
552

553
    mavlink_message_t msg{};
×
554
    mavlink_msg_camera_capture_status_pack(
×
555
        _server_component_impl->get_own_system_id(),
×
556
        _server_component_impl->get_own_component_id(),
×
557
        &msg,
558
        static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
559
        image_status,
560
        video_status,
561
        _image_capture_timer_interval_s,
562
        recording_time_ms,
563
        available_capacity,
564
        _image_capture_count);
565

566
    _server_component_impl->send_message(msg);
×
567

568
    // ack was already sent
569
    return std::nullopt;
×
570
}
571

572
std::optional<mavlink_message_t>
573
CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::CommandLong& command)
×
574
{
575
    auto reset = static_cast<bool>(command.params.param1);
×
576

577
    UNUSED(reset);
×
578

579
    LogDebug() << "unsupported reset camera settings request";
×
580

581
    return _server_component_impl->make_command_ack_message(
×
582
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
583
}
584

585
std::optional<mavlink_message_t>
586
CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandLong& command)
×
587
{
588
    auto camera_mode = static_cast<CAMERA_MODE>(command.params.param2);
×
589

590
    UNUSED(camera_mode);
×
591

592
    LogDebug() << "unsupported set camera mode request";
×
593

594
    return _server_component_impl->make_command_ack_message(
×
595
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
596
}
597

598
std::optional<mavlink_message_t>
599
CameraServerImpl::process_set_camera_zoom(const MavlinkCommandReceiver::CommandLong& command)
×
600
{
601
    auto zoom_type = static_cast<CAMERA_ZOOM_TYPE>(command.params.param1);
×
602
    auto zoom_value = command.params.param2;
×
603

604
    UNUSED(zoom_type);
×
605
    UNUSED(zoom_value);
×
606

607
    LogDebug() << "unsupported set camera zoom request";
×
608

609
    return _server_component_impl->make_command_ack_message(
×
610
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
611
}
612

613
std::optional<mavlink_message_t>
614
CameraServerImpl::process_set_camera_focus(const MavlinkCommandReceiver::CommandLong& command)
×
615
{
616
    auto focus_type = static_cast<SET_FOCUS_TYPE>(command.params.param1);
×
617
    auto focus_value = command.params.param2;
×
618

619
    UNUSED(focus_type);
×
620
    UNUSED(focus_value);
×
621

622
    LogDebug() << "unsupported set camera focus request";
×
623

624
    return _server_component_impl->make_command_ack_message(
×
625
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
626
}
627

628
std::optional<mavlink_message_t>
629
CameraServerImpl::process_set_storage_usage(const MavlinkCommandReceiver::CommandLong& command)
×
630
{
631
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
632
    auto usage = static_cast<STORAGE_USAGE_FLAG>(command.params.param2);
×
633

634
    UNUSED(storage_id);
×
635
    UNUSED(usage);
×
636

637
    LogDebug() << "unsupported set storage usage request";
×
638

639
    return _server_component_impl->make_command_ack_message(
×
640
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
641
}
642

643
std::optional<mavlink_message_t>
644
CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
645
{
646
    auto interval_s = command.params.param2;
×
647
    auto total_images = static_cast<int32_t>(command.params.param3);
×
648
    auto seq_number = static_cast<int32_t>(command.params.param4);
×
649

650
    LogDebug() << "received image start capture request - interval: " << +interval_s
×
651
               << " total: " << +total_images << " index: " << +seq_number;
×
652

653
    // TODO: validate parameters and return MAV_RESULT_DENIED not valid
654

655
    stop_image_capture_interval();
×
656

657
    if (_take_photo_callbacks.empty()) {
×
658
        LogDebug() << "image capture requested with no take photo subscriber";
×
659
        return _server_component_impl->make_command_ack_message(
×
660
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
661
    }
662

663
    // single image capture
664
    if (total_images == 1) {
×
665
        if (seq_number <= _image_capture_count) {
×
666
            LogDebug() << "received duplicate single image capture request";
×
667
            // We know we already captured this request, so we can just ack it.
668
            return _server_component_impl->make_command_ack_message(
×
669
                command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
670
        }
671

672
        // MAV_RESULT_ACCEPTED must be sent before CAMERA_IMAGE_CAPTURED
673
        auto ack_msg = _server_component_impl->make_command_ack_message(
×
674
            command, MAV_RESULT::MAV_RESULT_IN_PROGRESS);
×
675
        _server_component_impl->send_message(ack_msg);
×
676

677
        _last_take_photo_command = command;
×
678

679
        // FIXME: why is this needed to prevent dropping messages?
680
        // std::this_thread::sleep_for(std::chrono::milliseconds(100));
681

682
        _take_photo_callbacks(seq_number);
×
683

684
        return std::nullopt;
×
685
    }
686

687
    start_image_capture_interval(interval_s, total_images, seq_number);
×
688

689
    return _server_component_impl->make_command_ack_message(
×
690
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
691
}
692

693
std::optional<mavlink_message_t>
694
CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
×
695
{
696
    LogDebug() << "received image stop capture request";
×
697

698
    // REVISIT: should we return something other that MAV_RESULT_ACCEPTED if
699
    // there is not currently a capture interval active?
700
    stop_image_capture_interval();
×
701

702
    return _server_component_impl->make_command_ack_message(
×
703
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
704
}
705

706
std::optional<mavlink_message_t> CameraServerImpl::process_camera_image_capture_request(
×
707
    const MavlinkCommandReceiver::CommandLong& command)
708
{
709
    auto seq_number = static_cast<uint32_t>(command.params.param1);
×
710

711
    UNUSED(seq_number);
×
712

713
    LogDebug() << "unsupported image capture request";
×
714

715
    return _server_component_impl->make_command_ack_message(
×
716
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
717
}
718

719
std::optional<mavlink_message_t>
720
CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
721
{
722
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
723
    auto status_frequency = command.params.param2;
×
724

725
    UNUSED(stream_id);
×
726
    UNUSED(status_frequency);
×
727

728
    LogDebug() << "unsupported video start capture request";
×
729

730
    return _server_component_impl->make_command_ack_message(
×
731
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
732
}
733

734
std::optional<mavlink_message_t>
735
CameraServerImpl::process_video_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
×
736
{
737
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
738

739
    UNUSED(stream_id);
×
740

741
    LogDebug() << "unsupported video stop capture request";
×
742

743
    return _server_component_impl->make_command_ack_message(
×
744
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
745
}
746

747
std::optional<mavlink_message_t>
748
CameraServerImpl::process_video_start_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
749
{
750
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
751

752
    UNUSED(stream_id);
×
753

754
    LogDebug() << "unsupported video start streaming request";
×
755

756
    return _server_component_impl->make_command_ack_message(
×
757
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
758
}
759

760
std::optional<mavlink_message_t>
761
CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
762
{
763
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
764

765
    UNUSED(stream_id);
×
766

767
    LogDebug() << "unsupported video stop streaming request";
×
768

769
    return _server_component_impl->make_command_ack_message(
×
770
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
771
}
772

773
std::optional<mavlink_message_t> CameraServerImpl::process_video_stream_information_request(
×
774
    const MavlinkCommandReceiver::CommandLong& command)
775
{
776
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
777

778
    UNUSED(stream_id);
×
779

780
    LogDebug() << "unsupported video stream information request";
×
781

782
    return _server_component_impl->make_command_ack_message(
×
783
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
784
}
785

786
std::optional<mavlink_message_t> CameraServerImpl::process_video_stream_status_request(
×
787
    const MavlinkCommandReceiver::CommandLong& command)
788
{
789
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
790

791
    UNUSED(stream_id);
×
792

793
    LogDebug() << "unsupported video stream status request";
×
794

795
    return _server_component_impl->make_command_ack_message(
×
796
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
797
}
798

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