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

mavlink / MAVSDK / 6568658631

19 Oct 2023 01:31AM UTC coverage: 31.23% (+0.02%) from 31.215%
6568658631

push

github

web-flow
Merge pull request #2155 from mavlink/pr-static-fixes

Threading fixes, MAVLink sequence number cleanup

1386 of 1386 new or added lines in 46 files covered. (100.0%)

7906 of 25315 relevant lines covered (31.23%)

23.54 hits per line

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

9.66
/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 command_ack = _server_component_impl->make_command_ack_message(
×
233
                _last_take_photo_command, MAV_RESULT_ACCEPTED);
×
234
            _server_component_impl->send_command_ack(command_ack);
×
235
            // Only break and send the captured below.
236
            break;
×
237
        }
238
        case CameraServer::TakePhotoFeedback::Busy: {
×
239
            auto command_ack = _server_component_impl->make_command_ack_message(
×
240
                _last_take_photo_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
241
            _server_component_impl->send_command_ack(command_ack);
×
242
            return CameraServer::Result::Success;
×
243
        }
244
        case CameraServer::TakePhotoFeedback::Failed: {
×
245
            auto command_ack = _server_component_impl->make_command_ack_message(
×
246
                _last_take_photo_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
247
            _server_component_impl->send_command_ack(command_ack);
×
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
    // TODO: this should be a broadcast message
269
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
270
        mavlink_message_t message{};
×
271
        mavlink_msg_camera_image_captured_pack_chan(
×
272
            mavlink_address.system_id,
×
273
            mavlink_address.component_id,
×
274
            channel,
275
            &message,
276
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
277
            capture_info.time_utc_us,
×
278
            camera_id,
279
            static_cast<int32_t>(capture_info.position.latitude_deg * 1e7),
×
280
            static_cast<int32_t>(capture_info.position.longitude_deg * 1e7),
×
281
            static_cast<int32_t>(capture_info.position.absolute_altitude_m * 1e3f),
×
282
            static_cast<int32_t>(capture_info.position.relative_altitude_m * 1e3f),
×
283
            attitude_quaternion,
×
284
            capture_info.index,
285
            capture_info.is_success,
×
286
            capture_info.file_url.c_str());
287
        return message;
×
288
    });
289
    LogDebug() << "sent camera image captured msg - index: " << +capture_info.index;
×
290

291
    return CameraServer::Result::Success;
×
292
}
293

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

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

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

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

322
    _is_image_capture_interval_set = true;
×
323
    _image_capture_timer_interval_s = interval_s;
×
324
}
×
325

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

335
    _image_capture_timer_cookie = nullptr;
1✔
336
    _is_image_capture_interval_set = false;
1✔
337
    _image_capture_timer_interval_s = 0;
1✔
338
}
1✔
339

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

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

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

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

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

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

370
    // capability flags are determined by subscriptions
371
    uint32_t capability_flags{};
×
372

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

377
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
378
        mavlink_message_t message{};
×
379
        mavlink_msg_camera_information_pack_chan(
×
380
            mavlink_address.system_id,
×
381
            mavlink_address.component_id,
×
382
            channel,
383
            &message,
384
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
385
            reinterpret_cast<const uint8_t*>(_information.vendor_name.c_str()),
×
386
            reinterpret_cast<const uint8_t*>(_information.model_name.c_str()),
×
387
            firmware_version,
×
388
            _information.focal_length_mm,
389
            _information.horizontal_sensor_size_mm,
390
            _information.vertical_sensor_size_mm,
391
            _information.horizontal_resolution_px,
×
392
            _information.vertical_resolution_px,
×
393
            _information.lens_id,
×
394
            capability_flags,
×
395
            _information.definition_file_version,
×
396
            _information.definition_file_uri.c_str());
397
        return message;
×
398
    });
399
    LogDebug() << "sent info msg";
×
400

401
    // ack was already sent
402
    return std::nullopt;
×
403
}
404

405
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_settings_request(
×
406
    const MavlinkCommandReceiver::CommandLong& command)
407
{
408
    auto settings = static_cast<bool>(command.params.param1);
×
409

410
    if (!settings) {
×
411
        LogDebug() << "early settings return";
×
412
        return _server_component_impl->make_command_ack_message(
×
413
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
414
    }
415

416
    // ack needs to be sent before camera information message
417
    auto ack_msg =
×
418
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
419
    _server_component_impl->send_command_ack(ack_msg);
×
420
    LogDebug() << "sent settings ack";
×
421

422
    // FIXME: why is this needed to prevent dropping messages?
423
    std::this_thread::sleep_for(std::chrono::milliseconds(100));
×
424

425
    // unsupported
426
    const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE;
×
427
    const float zoom_level = 0;
×
428
    const float focus_level = 0;
×
429

430
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
431
        mavlink_message_t message{};
×
432
        mavlink_msg_camera_settings_pack_chan(
×
433
            mavlink_address.system_id,
×
434
            mavlink_address.component_id,
×
435
            channel,
436
            &message,
437
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
438
            mode_id,
439
            zoom_level,
×
440
            focus_level);
×
441
        return message;
×
442
    });
443
    LogDebug() << "sent settings msg";
×
444

445
    // ack was already sent
446
    return std::nullopt;
×
447
}
448

449
std::optional<mavlink_command_ack_t> CameraServerImpl::process_storage_information_request(
×
450
    const MavlinkCommandReceiver::CommandLong& command)
451
{
452
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
453
    auto information = static_cast<bool>(command.params.param2);
×
454

455
    if (!information) {
×
456
        LogDebug() << "early storage return";
×
457
        return _server_component_impl->make_command_ack_message(
×
458
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
459
    }
460

461
    // ack needs to be sent before camera information message
462
    auto command_ack =
×
463
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
464
    _server_component_impl->send_command_ack(command_ack);
×
465
    LogDebug() << "sent storage ack";
×
466

467
    // FIXME: why is this needed to prevent dropping messages?
468
    std::this_thread::sleep_for(std::chrono::milliseconds(100));
×
469

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

484
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
485
        mavlink_message_t message{};
×
486
        mavlink_msg_storage_information_pack_chan(
×
487
            mavlink_address.system_id,
×
488
            mavlink_address.component_id,
×
489
            channel,
490
            &message,
491
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
492
            storage_id,
×
493
            storage_count,
494
            status,
495
            total_capacity,
×
496
            used_capacity,
×
497
            available_capacity,
×
498
            read_speed,
×
499
            write_speed,
×
500
            type,
501
            name.data(),
×
502
            storage_usage);
503

504
        return message;
×
505
    });
506

507
    LogDebug() << "sent storage msg";
×
508

509
    // ack was already sent
510
    return std::nullopt;
×
511
}
512

513
std::optional<mavlink_command_ack_t>
514
CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLong& command)
×
515
{
516
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
517
    auto format = static_cast<bool>(command.params.param2);
×
518
    auto reset_image_log = static_cast<bool>(command.params.param3);
×
519

520
    UNUSED(storage_id);
×
521
    UNUSED(format);
×
522
    UNUSED(reset_image_log);
×
523

524
    LogDebug() << "unsupported storage format request";
×
525

526
    return _server_component_impl->make_command_ack_message(
×
527
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
528
}
529

530
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_capture_status_request(
×
531
    const MavlinkCommandReceiver::CommandLong& command)
532
{
533
    auto capture_status = static_cast<bool>(command.params.param1);
×
534

535
    if (!capture_status) {
×
536
        return _server_component_impl->make_command_ack_message(
×
537
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
538
    }
539

540
    // ack needs to be sent before camera information message
541
    auto command_ack =
×
542
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
543
    _server_component_impl->send_command_ack(command_ack);
×
544

545
    // FIXME: why is this needed to prevent dropping messages?
546
    std::this_thread::sleep_for(std::chrono::milliseconds(100));
×
547

548
    uint8_t image_status{};
×
549

550
    if (_is_image_capture_in_progress) {
×
551
        image_status |= StatusFlags::IN_PROGRESS;
×
552
    }
553

554
    if (_is_image_capture_interval_set) {
×
555
        image_status |= StatusFlags::INTERVAL_SET;
×
556
    }
557

558
    // unsupported
559
    const uint8_t video_status = 0;
×
560
    const uint32_t recording_time_ms = 0;
×
561
    const float available_capacity = 0;
×
562

563
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
564
        mavlink_message_t message{};
×
565
        mavlink_msg_camera_capture_status_pack_chan(
×
566
            mavlink_address.system_id,
×
567
            mavlink_address.component_id,
×
568
            channel,
569
            &message,
570
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
571
            image_status,
×
572
            video_status,
573
            _image_capture_timer_interval_s,
574
            recording_time_ms,
575
            available_capacity,
×
576
            _image_capture_count);
577
        return message;
×
578
    });
579

580
    // ack was already sent
581
    return std::nullopt;
×
582
}
583

584
std::optional<mavlink_command_ack_t>
585
CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::CommandLong& command)
×
586
{
587
    auto reset = static_cast<bool>(command.params.param1);
×
588

589
    UNUSED(reset);
×
590

591
    LogDebug() << "unsupported reset camera settings request";
×
592

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

597
std::optional<mavlink_command_ack_t>
598
CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandLong& command)
×
599
{
600
    auto camera_mode = static_cast<CAMERA_MODE>(command.params.param2);
×
601

602
    UNUSED(camera_mode);
×
603

604
    LogDebug() << "unsupported set camera mode request";
×
605

606
    return _server_component_impl->make_command_ack_message(
×
607
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
608
}
609

610
std::optional<mavlink_command_ack_t>
611
CameraServerImpl::process_set_camera_zoom(const MavlinkCommandReceiver::CommandLong& command)
×
612
{
613
    auto zoom_type = static_cast<CAMERA_ZOOM_TYPE>(command.params.param1);
×
614
    auto zoom_value = command.params.param2;
×
615

616
    UNUSED(zoom_type);
×
617
    UNUSED(zoom_value);
×
618

619
    LogDebug() << "unsupported set camera zoom request";
×
620

621
    return _server_component_impl->make_command_ack_message(
×
622
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
623
}
624

625
std::optional<mavlink_command_ack_t>
626
CameraServerImpl::process_set_camera_focus(const MavlinkCommandReceiver::CommandLong& command)
×
627
{
628
    auto focus_type = static_cast<SET_FOCUS_TYPE>(command.params.param1);
×
629
    auto focus_value = command.params.param2;
×
630

631
    UNUSED(focus_type);
×
632
    UNUSED(focus_value);
×
633

634
    LogDebug() << "unsupported set camera focus request";
×
635

636
    return _server_component_impl->make_command_ack_message(
×
637
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
638
}
639

640
std::optional<mavlink_command_ack_t>
641
CameraServerImpl::process_set_storage_usage(const MavlinkCommandReceiver::CommandLong& command)
×
642
{
643
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
644
    auto usage = static_cast<STORAGE_USAGE_FLAG>(command.params.param2);
×
645

646
    UNUSED(storage_id);
×
647
    UNUSED(usage);
×
648

649
    LogDebug() << "unsupported set storage usage request";
×
650

651
    return _server_component_impl->make_command_ack_message(
×
652
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
653
}
654

655
std::optional<mavlink_command_ack_t>
656
CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
657
{
658
    auto interval_s = command.params.param2;
×
659
    auto total_images = static_cast<int32_t>(command.params.param3);
×
660
    auto seq_number = static_cast<int32_t>(command.params.param4);
×
661

662
    LogDebug() << "received image start capture request - interval: " << +interval_s
×
663
               << " total: " << +total_images << " index: " << +seq_number;
×
664

665
    // TODO: validate parameters and return MAV_RESULT_DENIED not valid
666

667
    stop_image_capture_interval();
×
668

669
    if (_take_photo_callbacks.empty()) {
×
670
        LogDebug() << "image capture requested with no take photo subscriber";
×
671
        return _server_component_impl->make_command_ack_message(
×
672
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
673
    }
674

675
    // single image capture
676
    if (total_images == 1) {
×
677
        if (seq_number <= _image_capture_count) {
×
678
            LogDebug() << "received duplicate single image capture request";
×
679
            // We know we already captured this request, so we can just ack it.
680
            return _server_component_impl->make_command_ack_message(
×
681
                command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
682
        }
683

684
        // MAV_RESULT_ACCEPTED must be sent before CAMERA_IMAGE_CAPTURED
685
        auto command_ack = _server_component_impl->make_command_ack_message(
×
686
            command, MAV_RESULT::MAV_RESULT_IN_PROGRESS);
×
687
        _server_component_impl->send_command_ack(command_ack);
×
688

689
        _last_take_photo_command = command;
×
690

691
        // FIXME: why is this needed to prevent dropping messages?
692
        // std::this_thread::sleep_for(std::chrono::milliseconds(100));
693

694
        _take_photo_callbacks(seq_number);
×
695

696
        return std::nullopt;
×
697
    }
698

699
    start_image_capture_interval(interval_s, total_images, seq_number);
×
700

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

705
std::optional<mavlink_command_ack_t>
706
CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
×
707
{
708
    LogDebug() << "received image stop capture request";
×
709

710
    // REVISIT: should we return something other that MAV_RESULT_ACCEPTED if
711
    // there is not currently a capture interval active?
712
    stop_image_capture_interval();
×
713

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

718
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_image_capture_request(
×
719
    const MavlinkCommandReceiver::CommandLong& command)
720
{
721
    auto seq_number = static_cast<uint32_t>(command.params.param1);
×
722

723
    UNUSED(seq_number);
×
724

725
    LogDebug() << "unsupported image capture request";
×
726

727
    return _server_component_impl->make_command_ack_message(
×
728
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
729
}
730

731
std::optional<mavlink_command_ack_t>
732
CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
733
{
734
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
735
    auto status_frequency = command.params.param2;
×
736

737
    UNUSED(stream_id);
×
738
    UNUSED(status_frequency);
×
739

740
    LogDebug() << "unsupported video start capture request";
×
741

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

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

751
    UNUSED(stream_id);
×
752

753
    LogDebug() << "unsupported video stop capture request";
×
754

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

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

764
    UNUSED(stream_id);
×
765

766
    LogDebug() << "unsupported video start streaming request";
×
767

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

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

777
    UNUSED(stream_id);
×
778

779
    LogDebug() << "unsupported video stop streaming request";
×
780

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

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

790
    UNUSED(stream_id);
×
791

792
    LogDebug() << "unsupported video stream information request";
×
793

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

798
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_status_request(
×
799
    const MavlinkCommandReceiver::CommandLong& command)
800
{
801
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
802

803
    UNUSED(stream_id);
×
804

805
    LogDebug() << "unsupported video stream status request";
×
806

807
    return _server_component_impl->make_command_ack_message(
×
808
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
809
}
810

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