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

mavlink / MAVSDK / 16461643550

23 Jul 2025 04:35AM UTC coverage: 45.187% (+0.09%) from 45.093%
16461643550

Pull #2621

github

web-flow
Merge 136e24850 into ae05b10ff
Pull Request #2621: CameraServer improvements

43 of 120 new or added lines in 1 file covered. (35.83%)

307 existing lines in 2 files now uncovered.

15426 of 34138 relevant lines covered (45.19%)

290.49 hits per line

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

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

4
namespace mavsdk {
5

6
template class CallbackList<int32_t>;
7
template class CallbackList<CameraServer::TrackPoint>;
8
template class CallbackList<CameraServer::TrackRectangle>;
9

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

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

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

150
    _server_component_impl->register_mavlink_command_handler(
9✔
151
        MAV_CMD_CAMERA_TRACK_RECTANGLE,
152
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
153
            return process_track_rectangle_command(command);
×
154
        },
155
        this);
156

157
    _server_component_impl->register_mavlink_command_handler(
9✔
158
        MAV_CMD_CAMERA_STOP_TRACKING,
159
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
160
            return process_track_off_command(command);
×
161
        },
162
        this);
163
    _server_component_impl->register_mavlink_command_handler(
9✔
164
        MAV_CMD_SET_MESSAGE_INTERVAL,
165
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
166
            return process_set_message_interval(command);
×
167
        },
168
        this);
169
}
9✔
170

171
void CameraServerImpl::deinit()
9✔
172
{
173
    stop_image_capture_interval();
9✔
174
    stop_sending_capture_status();
9✔
175
    _server_component_impl->unregister_all_mavlink_command_handlers(this);
9✔
176

177
    std::lock_guard lg(_mutex);
9✔
178
    _take_photo_callbacks.clear();
9✔
179
    _start_video_callbacks.clear();
9✔
180
    _stop_video_callbacks.clear();
9✔
181
    _start_video_streaming_callbacks.clear();
9✔
182
    _stop_video_streaming_callbacks.clear();
9✔
183
    _set_mode_callbacks.clear();
9✔
184
    _storage_information_callbacks.clear();
9✔
185
    _capture_status_callbacks.clear();
9✔
186
    _format_storage_callbacks.clear();
9✔
187
    _reset_settings_callbacks.clear();
9✔
188
    _tracking_point_callbacks.clear();
9✔
189
    _tracking_rectangle_callbacks.clear();
9✔
190
    _tracking_off_callbacks.clear();
9✔
191
    _zoom_in_start_callbacks.clear();
9✔
192
    _zoom_out_start_callbacks.clear();
9✔
193
    _zoom_stop_callbacks.clear();
9✔
194
    _zoom_range_callbacks.clear();
9✔
195
}
9✔
196

197
bool CameraServerImpl::is_command_sender_ok(const MavlinkCommandReceiver::CommandLong& command)
×
198
{
199
    if (command.target_system_id != 0 &&
×
200
        command.target_system_id != _server_component_impl->get_own_system_id()) {
×
201
        return false;
×
202
    } else {
203
        return true;
×
204
    }
205
}
206

207
void CameraServerImpl::set_tracking_point_status(CameraServer::TrackPoint tracked_point)
×
208
{
209
    std::lock_guard<std::mutex> lg{_mutex};
×
210
    _tracking_mode = TrackingMode::POINT;
×
211
    _tracked_point = tracked_point;
×
212
}
×
213

214
void CameraServerImpl::set_tracking_rectangle_status(CameraServer::TrackRectangle tracked_rectangle)
×
215
{
216
    std::lock_guard<std::mutex> lg{_mutex};
×
217
    _tracking_mode = TrackingMode::RECTANGLE;
×
218
    _tracked_rectangle = tracked_rectangle;
×
219
}
×
220

221
void CameraServerImpl::set_tracking_off_status()
×
222
{
223
    std::lock_guard<std::mutex> lg{_mutex};
×
224
    _tracking_mode = TrackingMode::NONE;
×
225
}
×
226

227
bool CameraServerImpl::parse_version_string(const std::string& version_str)
9✔
228
{
229
    uint32_t unused;
9✔
230

231
    return parse_version_string(version_str, unused);
9✔
232
}
233

234
bool CameraServerImpl::parse_version_string(const std::string& version_str, uint32_t& version)
18✔
235
{
236
    // empty string means no version
237
    if (version_str.empty()) {
18✔
238
        version = 0;
×
239

240
        return true;
×
241
    }
242

243
    uint8_t major{}, minor{}, patch{}, dev{};
18✔
244

245
    auto ret = sscanf(version_str.c_str(), "%hhu.%hhu.%hhu.%hhu", &major, &minor, &patch, &dev);
18✔
246

247
    if (ret == EOF) {
18✔
248
        return false;
×
249
    }
250

251
    // pack version according to MAVLINK spec
252
    version = dev << 24 | patch << 16 | minor << 8 | major;
18✔
253

254
    return true;
18✔
255
}
256

257
CameraServer::Result CameraServerImpl::set_information(CameraServer::Information information)
9✔
258
{
259
    if (!parse_version_string(information.firmware_version)) {
9✔
260
        LogDebug() << "incorrectly formatted firmware version string: "
×
261
                   << information.firmware_version;
×
262
        return CameraServer::Result::WrongArgument;
×
263
    }
264

265
    std::lock_guard<std::mutex> lg{_mutex};
9✔
266

267
    // TODO: validate information.definition_file_uri
268

269
    _is_information_set = true;
9✔
270
    _information = information;
9✔
271

272
    return CameraServer::Result::Success;
9✔
273
}
9✔
274

275
CameraServer::Result
276
CameraServerImpl::set_video_streaming(CameraServer::VideoStreaming video_streaming)
1✔
277
{
278
    // TODO: validate uri length
279

280
    std::lock_guard<std::mutex> lg{_mutex};
1✔
281

282
    _is_video_streaming_set = true;
1✔
283
    _video_streaming = video_streaming;
1✔
284

285
    return CameraServer::Result::Success;
2✔
286
}
1✔
287

288
CameraServer::Result CameraServerImpl::set_in_progress(bool in_progress)
×
289
{
290
    _is_image_capture_in_progress = in_progress;
×
291

292
    send_capture_status();
×
293
    return CameraServer::Result::Success;
×
294
}
295

296
CameraServer::TakePhotoHandle
297
CameraServerImpl::subscribe_take_photo(const CameraServer::TakePhotoCallback& callback)
2✔
298
{
299
    std::lock_guard<std::mutex> lg{_mutex};
2✔
300
    return _take_photo_callbacks.subscribe(callback);
2✔
301
}
2✔
302

303
void CameraServerImpl::unsubscribe_take_photo(CameraServer::TakePhotoHandle handle)
×
304
{
305
    std::lock_guard<std::mutex> lg{_mutex};
×
306
    _take_photo_callbacks.unsubscribe(handle);
×
307
}
×
308

309
CameraServer::Result CameraServerImpl::respond_take_photo(
4✔
310
    CameraServer::CameraFeedback take_photo_feedback, CameraServer::CaptureInfo capture_info)
311
{
312
    bool should_send_capture_status = false;
4✔
313

314
    {
315
        std::lock_guard<std::mutex> lg{_mutex};
4✔
316

317
        // If capture_info.index == INT32_MIN, it means this was an interval
318
        // capture rather than a single image capture.
319
        if (capture_info.index != INT32_MIN) {
4✔
320
            // We expect each capture to be the next sequential number.
321
            // If _image_capture_count == 0, we ignore since it means that this is
322
            // the first photo since the plugin was initialized.
323
            if (_image_capture_count != 0 && capture_info.index != _image_capture_count + 1) {
4✔
NEW
324
                LogErr() << "unexpected image index, expecting " << +(_image_capture_count + 1)
×
NEW
325
                         << " but was " << +capture_info.index;
×
326
            }
327

328
            _image_capture_count = capture_info.index;
4✔
329
        }
330

331
        // Log the command details to help debug
332
        LogDebug() << "Responding to take photo command: " << "target_system_id: "
8✔
333
                   << static_cast<int>(_last_take_photo_command.target_system_id)
8✔
334
                   << ", target_component_id: "
4✔
335
                   << static_cast<int>(_last_take_photo_command.target_component_id)
8✔
336
                   << ", command: " << _last_take_photo_command.command;
16✔
337

338
        switch (take_photo_feedback) {
4✔
NEW
339
            default:
×
340
                // Fallthrough
341
            case CameraServer::CameraFeedback::Unknown:
NEW
342
                return CameraServer::Result::Error;
×
343
            case CameraServer::CameraFeedback::Ok: {
4✔
344
                // Check for error above
345
                auto command_ack = _server_component_impl->make_command_ack_message(
4✔
346
                    _last_take_photo_command, MAV_RESULT_ACCEPTED);
4✔
347
                _server_component_impl->send_command_ack(command_ack);
4✔
348
                should_send_capture_status = true;
4✔
349
                // Only break and send the captured below.
350
                break;
4✔
351
            }
NEW
352
            case CameraServer::CameraFeedback::Busy: {
×
NEW
353
                auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
354
                    _last_take_photo_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
NEW
355
                _server_component_impl->send_command_ack(command_ack);
×
NEW
356
                return CameraServer::Result::Success;
×
357
            }
358

NEW
359
            case CameraServer::CameraFeedback::Failed: {
×
NEW
360
                auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
361
                    _last_take_photo_command, MAV_RESULT_FAILED);
×
NEW
362
                _server_component_impl->send_command_ack(command_ack);
×
NEW
363
                return CameraServer::Result::Success;
×
364
            }
365
        }
366

367
        // REVISIT: Should we cache all CaptureInfo in memory for single image
368
        // captures so that we can respond to requests for lost CAMERA_IMAGE_CAPTURED
369
        // messages without calling back to user code?
370

371
        static const uint8_t camera_id = 0; // deprecated unused field
372

373
        const float attitude_quaternion[] = {
4✔
374
            capture_info.attitude_quaternion.w,
4✔
375
            capture_info.attitude_quaternion.x,
4✔
376
            capture_info.attitude_quaternion.y,
4✔
377
            capture_info.attitude_quaternion.z,
4✔
378
        };
4✔
379

380
        // There needs to be enough data to be copied mavlink internal.
381
        capture_info.file_url.resize(205);
4✔
382

383
        // TODO: this should be a broadcast message
384
        _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
4✔
385
            mavlink_message_t message{};
4✔
386
            mavlink_msg_camera_image_captured_pack_chan(
12✔
387
                mavlink_address.system_id,
4✔
388
                mavlink_address.component_id,
4✔
389
                channel,
390
                &message,
391
                static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
4✔
392
                capture_info.time_utc_us,
4✔
393
                camera_id,
394
                static_cast<int32_t>(capture_info.position.latitude_deg * 1e7),
4✔
395
                static_cast<int32_t>(capture_info.position.longitude_deg * 1e7),
4✔
396
                static_cast<int32_t>(capture_info.position.absolute_altitude_m * 1e3f),
4✔
397
                static_cast<int32_t>(capture_info.position.relative_altitude_m * 1e3f),
4✔
398
                attitude_quaternion,
4✔
399
                capture_info.index,
400
                capture_info.is_success,
4✔
401
                capture_info.file_url.c_str());
402
            return message;
4✔
403
        });
404
        LogDebug() << "sent camera image captured msg - index: " << +capture_info.index;
4✔
405

406
    } // Release mutex
4✔
407

408
    if (should_send_capture_status) {
4✔
409
        send_capture_status();
4✔
410
    }
411

412
    return CameraServer::Result::Success;
4✔
413
}
414

415
CameraServer::StartVideoHandle
416
CameraServerImpl::subscribe_start_video(const CameraServer::StartVideoCallback& callback)
×
417
{
418
    std::lock_guard<std::mutex> lg{_mutex};
×
419
    return _start_video_callbacks.subscribe(callback);
×
420
}
×
421

422
void CameraServerImpl::unsubscribe_start_video(CameraServer::StartVideoHandle handle)
×
423
{
424
    std::lock_guard<std::mutex> lg{_mutex};
×
425
    _start_video_callbacks.unsubscribe(handle);
×
426
}
×
427

428
CameraServer::Result
429
CameraServerImpl::respond_start_video(CameraServer::CameraFeedback start_video_feedback)
×
430
{
NEW
431
    std::lock_guard<std::mutex> lg{_mutex};
×
432

NEW
433
    switch (start_video_feedback) {
×
NEW
434
        default:
×
435
            // Fallthrough
436
        case CameraServer::CameraFeedback::Unknown:
NEW
437
            return CameraServer::Result::Error;
×
NEW
438
        case CameraServer::CameraFeedback::Ok: {
×
NEW
439
            auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
440
                _last_start_video_command, MAV_RESULT_ACCEPTED);
×
NEW
441
            _server_component_impl->send_command_ack(command_ack);
×
NEW
442
            send_capture_status();
×
NEW
443
            return CameraServer::Result::Success;
×
444
        }
NEW
445
        case CameraServer::CameraFeedback::Busy: {
×
NEW
446
            auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
447
                _last_start_video_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
NEW
448
            _server_component_impl->send_command_ack(command_ack);
×
NEW
449
            return CameraServer::Result::Success;
×
450
        }
NEW
451
        case CameraServer::CameraFeedback::Failed: {
×
NEW
452
            auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
453
                _last_start_video_command, MAV_RESULT_FAILED);
×
NEW
454
            _server_component_impl->send_command_ack(command_ack);
×
NEW
455
            return CameraServer::Result::Success;
×
456
        }
457
    }
NEW
458
}
×
459

460
CameraServer::StopVideoHandle
NEW
461
CameraServerImpl::subscribe_stop_video(const CameraServer::StopVideoCallback& callback)
×
462
{
NEW
463
    std::lock_guard<std::mutex> lg{_mutex};
×
NEW
464
    return _stop_video_callbacks.subscribe(callback);
×
465
}
×
466

NEW
467
void CameraServerImpl::unsubscribe_stop_video(CameraServer::StopVideoHandle handle)
×
468
{
UNCOV
469
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
470
    return _stop_video_callbacks.unsubscribe(handle);
×
471
}
×
472

473
CameraServer::Result
474
CameraServerImpl::respond_stop_video(CameraServer::CameraFeedback stop_video_feedback)
×
475
{
UNCOV
476
    std::lock_guard<std::mutex> lg{_mutex};
×
477

UNCOV
478
    switch (stop_video_feedback) {
×
479
        default:
×
480
            // Fallthrough
481
        case CameraServer::CameraFeedback::Unknown:
UNCOV
482
            return CameraServer::Result::Error;
×
UNCOV
483
        case CameraServer::CameraFeedback::Ok: {
×
484
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
485
                _last_stop_video_command, MAV_RESULT_ACCEPTED);
×
NEW
486
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
487
            send_capture_status();
×
NEW
488
            return CameraServer::Result::Success;
×
489
        }
NEW
490
        case CameraServer::CameraFeedback::Busy: {
×
NEW
491
            auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
492
                _last_stop_video_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
NEW
493
            _server_component_impl->send_command_ack(command_ack);
×
NEW
494
            return CameraServer::Result::Success;
×
495
        }
NEW
496
        case CameraServer::CameraFeedback::Failed: {
×
NEW
497
            auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
498
                _last_stop_video_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
NEW
499
            _server_component_impl->send_command_ack(command_ack);
×
NEW
500
            return CameraServer::Result::Success;
×
501
        }
502
    }
NEW
503
}
×
504

NEW
505
CameraServer::StartVideoStreamingHandle CameraServerImpl::subscribe_start_video_streaming(
×
506
    const CameraServer::StartVideoStreamingCallback& callback)
507
{
NEW
508
    std::lock_guard<std::mutex> lg{_mutex};
×
NEW
509
    return _start_video_streaming_callbacks.subscribe(callback);
×
NEW
510
}
×
511

NEW
512
void CameraServerImpl::unsubscribe_start_video_streaming(
×
513
    CameraServer::StartVideoStreamingHandle handle)
514
{
UNCOV
515
    std::lock_guard<std::mutex> lg{_mutex};
×
NEW
516
    return _start_video_streaming_callbacks.unsubscribe(handle);
×
NEW
517
}
×
518

NEW
519
CameraServer::Result CameraServerImpl::respond_start_video_streaming(
×
520
    CameraServer::CameraFeedback start_video_streaming_feedback)
521
{
NEW
522
    std::lock_guard<std::mutex> lg{_mutex};
×
523

UNCOV
524
    switch (start_video_streaming_feedback) {
×
525
        default:
×
526
            // Fallthrough
527
        case CameraServer::CameraFeedback::Unknown:
528
            return CameraServer::Result::Error;
×
529
        case CameraServer::CameraFeedback::Ok: {
×
530
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
531
                _last_start_video_streaming_command, MAV_RESULT_ACCEPTED);
×
532
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
533
            return CameraServer::Result::Success;
×
534
        }
535
        case CameraServer::CameraFeedback::Busy: {
×
536
            auto command_ack = _server_component_impl->make_command_ack_message(
×
537
                _last_start_video_streaming_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
538
            _server_component_impl->send_command_ack(command_ack);
×
539
            return CameraServer::Result::Success;
×
540
        }
UNCOV
541
        case CameraServer::CameraFeedback::Failed: {
×
542
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
543
                _last_start_video_streaming_command, MAV_RESULT_FAILED);
×
544
            _server_component_impl->send_command_ack(command_ack);
×
545
            return CameraServer::Result::Success;
×
546
        }
547
    }
548
}
×
549

550
CameraServer::StopVideoStreamingHandle CameraServerImpl::subscribe_stop_video_streaming(
×
551
    const CameraServer::StopVideoStreamingCallback& callback)
552
{
553
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
554
    return _stop_video_streaming_callbacks.subscribe(callback);
×
555
}
×
556

557
void CameraServerImpl::unsubscribe_stop_video_streaming(
×
558
    CameraServer::StopVideoStreamingHandle handle)
559
{
UNCOV
560
    std::lock_guard<std::mutex> lg{_mutex};
×
561
    return _stop_video_streaming_callbacks.unsubscribe(handle);
×
562
}
×
563

564
CameraServer::Result CameraServerImpl::respond_stop_video_streaming(
×
565
    CameraServer::CameraFeedback stop_video_streaming_feedback)
566
{
UNCOV
567
    std::lock_guard<std::mutex> lg{_mutex};
×
568

UNCOV
569
    switch (stop_video_streaming_feedback) {
×
570
        default:
×
571
            // Fallthrough
572
        case CameraServer::CameraFeedback::Unknown:
573
            return CameraServer::Result::Error;
×
574
        case CameraServer::CameraFeedback::Ok: {
×
575
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
576
                _last_stop_video_streaming_command, MAV_RESULT_ACCEPTED);
×
577
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
578
            return CameraServer::Result::Success;
×
579
        }
580
        case CameraServer::CameraFeedback::Busy: {
×
581
            auto command_ack = _server_component_impl->make_command_ack_message(
×
582
                _last_stop_video_streaming_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
583
            _server_component_impl->send_command_ack(command_ack);
×
584
            return CameraServer::Result::Success;
×
585
        }
UNCOV
586
        case CameraServer::CameraFeedback::Failed: {
×
587
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
588
                _last_stop_video_streaming_command, MAV_RESULT_FAILED);
×
589
            _server_component_impl->send_command_ack(command_ack);
×
590
            return CameraServer::Result::Success;
×
591
        }
592
    }
593
}
×
594

595
CameraServer::SetModeHandle
596
CameraServerImpl::subscribe_set_mode(const CameraServer::SetModeCallback& callback)
2✔
597
{
598
    std::lock_guard<std::mutex> lg{_mutex};
2✔
599
    return _set_mode_callbacks.subscribe(callback);
2✔
600
}
2✔
601

602
void CameraServerImpl::unsubscribe_set_mode(CameraServer::SetModeHandle handle)
1✔
603
{
604
    std::lock_guard<std::mutex> lg{_mutex};
1✔
605
    _set_mode_callbacks.unsubscribe(handle);
1✔
606
}
1✔
607

608
CameraServer::Result
609
CameraServerImpl::respond_set_mode(CameraServer::CameraFeedback set_mode_feedback)
2✔
610
{
611
    std::lock_guard<std::mutex> lg{_mutex};
2✔
612

613
    switch (set_mode_feedback) {
2✔
UNCOV
614
        default:
×
615
            // Fallthrough
616
        case CameraServer::CameraFeedback::Unknown:
UNCOV
617
            return CameraServer::Result::Error;
×
618
        case CameraServer::CameraFeedback::Ok: {
2✔
619
            auto command_ack = _server_component_impl->make_command_ack_message(
2✔
620
                _last_set_mode_command, MAV_RESULT_ACCEPTED);
2✔
621
            _server_component_impl->send_command_ack(command_ack);
2✔
622
            return CameraServer::Result::Success;
2✔
623
        }
UNCOV
624
        case CameraServer::CameraFeedback::Busy: {
×
UNCOV
625
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
626
                _last_set_mode_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
627
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
628
            return CameraServer::Result::Success;
×
629
        }
UNCOV
630
        case CameraServer::CameraFeedback::Failed: {
×
UNCOV
631
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
632
                _last_set_mode_command, MAV_RESULT_FAILED);
×
UNCOV
633
            _server_component_impl->send_command_ack(command_ack);
×
634
            return CameraServer::Result::Success;
×
635
        }
636
    }
637
}
2✔
638

639
CameraServer::StorageInformationHandle CameraServerImpl::subscribe_storage_information(
1✔
640
    const CameraServer::StorageInformationCallback& callback)
641
{
642
    std::lock_guard<std::mutex> lg{_mutex};
1✔
643
    return _storage_information_callbacks.subscribe(callback);
1✔
644
}
1✔
645

646
void CameraServerImpl::unsubscribe_storage_information(
×
647
    CameraServer::StorageInformationHandle handle)
648
{
UNCOV
649
    std::lock_guard<std::mutex> lg{_mutex};
×
650
    _storage_information_callbacks.unsubscribe(handle);
×
651
}
×
652

653
CameraServer::Result CameraServerImpl::respond_storage_information(
2✔
654
    CameraServer::CameraFeedback storage_information_feedback,
655
    CameraServer::StorageInformation storage_information)
656
{
657
    std::lock_guard<std::mutex> lg{_mutex};
2✔
658

659
    switch (storage_information_feedback) {
2✔
UNCOV
660
        default:
×
661
            // Fallthrough
662
        case CameraServer::CameraFeedback::Unknown:
UNCOV
663
            return CameraServer::Result::Error;
×
664
        case CameraServer::CameraFeedback::Ok: {
2✔
665
            auto command_ack = _server_component_impl->make_command_ack_message(
2✔
666
                _last_storage_information_command, MAV_RESULT_ACCEPTED);
2✔
667
            _server_component_impl->send_command_ack(command_ack);
2✔
668
            // break and send storage information
669
            break;
2✔
670
        }
671
        case CameraServer::CameraFeedback::Busy: {
×
UNCOV
672
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
673
                _last_storage_information_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
674
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
675
            return CameraServer::Result::Success;
×
676
        }
UNCOV
677
        case CameraServer::CameraFeedback::Failed: {
×
UNCOV
678
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
679
                _last_storage_information_command, MAV_RESULT_FAILED);
×
680
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
681
            return CameraServer::Result::Success;
×
682
        }
683
    }
684

685
    const uint8_t storage_count = 1;
2✔
686

687
    const float total_capacity = storage_information.total_storage_mib;
2✔
688
    const float used_capacity = storage_information.used_storage_mib;
2✔
689
    const float available_capacity = storage_information.available_storage_mib;
2✔
690
    const float read_speed = storage_information.read_speed_mib_s;
2✔
691
    const float write_speed = storage_information.write_speed_mib_s;
2✔
692

693
    auto status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
2✔
694
    switch (storage_information.storage_status) {
2✔
695
        case CameraServer::StorageInformation::StorageStatus::NotAvailable:
×
UNCOV
696
            status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
697
            break;
×
698
        case CameraServer::StorageInformation::StorageStatus::Unformatted:
×
699
            status = STORAGE_STATUS::STORAGE_STATUS_UNFORMATTED;
×
700
            break;
×
701
        case CameraServer::StorageInformation::StorageStatus::Formatted:
2✔
702
            status = STORAGE_STATUS::STORAGE_STATUS_READY;
2✔
703
            break;
2✔
UNCOV
704
        case CameraServer::StorageInformation::StorageStatus::NotSupported:
×
UNCOV
705
            status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
UNCOV
706
            break;
×
707
    }
708

709
    auto type = STORAGE_TYPE::STORAGE_TYPE_UNKNOWN;
2✔
710
    switch (storage_information.storage_type) {
2✔
UNCOV
711
        case CameraServer::StorageInformation::StorageType::UsbStick:
×
UNCOV
712
            type = STORAGE_TYPE::STORAGE_TYPE_USB_STICK;
×
UNCOV
713
            break;
×
UNCOV
714
        case CameraServer::StorageInformation::StorageType::Sd:
×
715
            type = STORAGE_TYPE::STORAGE_TYPE_SD;
×
716
            break;
×
717
        case CameraServer::StorageInformation::StorageType::Microsd:
×
718
            type = STORAGE_TYPE::STORAGE_TYPE_MICROSD;
×
719
            break;
×
720
        case CameraServer::StorageInformation::StorageType::Hd:
×
UNCOV
721
            type = STORAGE_TYPE::STORAGE_TYPE_HD;
×
UNCOV
722
            break;
×
UNCOV
723
        case CameraServer::StorageInformation::StorageType::Other:
×
724
            type = STORAGE_TYPE::STORAGE_TYPE_OTHER;
×
725
            break;
×
726
        default:
2✔
727
            break;
2✔
728
    }
729

730
    std::string name("");
4✔
731
    // This needs to be long enough, otherwise the memcpy in mavlink overflows.
732
    name.resize(32);
2✔
733
    const uint8_t storage_usage = 0;
2✔
734

735
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
2✔
736
        mavlink_message_t message{};
2✔
737
        mavlink_msg_storage_information_pack_chan(
4✔
738
            mavlink_address.system_id,
2✔
739
            mavlink_address.component_id,
2✔
740
            channel,
741
            &message,
742
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
2✔
743
            _last_storage_id,
2✔
744
            storage_count,
745
            status,
2✔
746
            total_capacity,
2✔
747
            used_capacity,
2✔
748
            available_capacity,
2✔
749
            read_speed,
2✔
750
            write_speed,
2✔
751
            type,
2✔
752
            name.data(),
2✔
753
            storage_usage);
754
        return message;
2✔
755
    });
756

757
    return CameraServer::Result::Success;
2✔
758
}
2✔
759

760
CameraServer::CaptureStatusHandle
UNCOV
761
CameraServerImpl::subscribe_capture_status(const CameraServer::CaptureStatusCallback& callback)
×
762
{
UNCOV
763
    CameraServer::CaptureStatusHandle handle;
×
UNCOV
764
    bool should_start_timer = false;
×
765

766
    {
UNCOV
767
        std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
768
        should_start_timer = _capture_status_callbacks.empty();
×
UNCOV
769
        handle = _capture_status_callbacks.subscribe(callback);
×
UNCOV
770
    }
×
771

UNCOV
772
    if (should_start_timer) {
×
UNCOV
773
        start_sending_capture_status();
×
774
    }
775

UNCOV
776
    return handle;
×
777
}
778

UNCOV
779
void CameraServerImpl::unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle)
×
780
{
781
    bool should_stop_timer = false;
×
782

783
    {
NEW
784
        std::lock_guard<std::mutex> lg{_mutex};
×
NEW
785
        _capture_status_callbacks.unsubscribe(handle);
×
NEW
786
        should_stop_timer = _capture_status_callbacks.empty();
×
NEW
787
    }
×
788

NEW
789
    if (should_stop_timer) {
×
NEW
790
        stop_sending_capture_status();
×
791
    }
NEW
792
}
×
793

NEW
794
CameraServer::Result CameraServerImpl::respond_capture_status(
×
795
    CameraServer::CameraFeedback capture_status_feedback,
796
    CameraServer::CaptureStatus capture_status)
797
{
798
    {
799
        std::lock_guard<std::mutex> lg{_mutex};
×
800

NEW
801
        switch (capture_status_feedback) {
×
NEW
802
            default:
×
803
                // Fallthrough
804
            case CameraServer::CameraFeedback::Unknown:
NEW
805
                return CameraServer::Result::Error;
×
NEW
806
            case CameraServer::CameraFeedback::Ok: {
×
NEW
807
                auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
808
                    _last_capture_status_command, MAV_RESULT_ACCEPTED);
×
NEW
809
                _server_component_impl->send_command_ack(command_ack);
×
810
                // break and send capture status
NEW
811
                break;
×
812
            }
UNCOV
813
            case CameraServer::CameraFeedback::Busy: {
×
814
                auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
815
                    _last_capture_status_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
816
                _server_component_impl->send_command_ack(command_ack);
×
UNCOV
817
                return CameraServer::Result::Success;
×
818
            }
819
            case CameraServer::CameraFeedback::Failed: {
×
UNCOV
820
                auto command_ack = _server_component_impl->make_command_ack_message(
×
821
                    _last_capture_status_command, MAV_RESULT_FAILED);
×
822
                _server_component_impl->send_command_ack(command_ack);
×
UNCOV
823
                return CameraServer::Result::Success;
×
824
            }
825
        }
826

827
        _capture_status = capture_status;
×
828
    }
×
829

UNCOV
830
    send_capture_status();
×
831

UNCOV
832
    return CameraServer::Result::Success;
×
833
}
834

835
CameraServer::FormatStorageHandle
836
CameraServerImpl::subscribe_format_storage(const CameraServer::FormatStorageCallback& callback)
1✔
837
{
838
    std::lock_guard<std::mutex> lg{_mutex};
1✔
839
    return _format_storage_callbacks.subscribe(callback);
1✔
840
}
1✔
841
void CameraServerImpl::unsubscribe_format_storage(CameraServer::FormatStorageHandle handle)
1✔
842
{
843
    std::lock_guard<std::mutex> lg{_mutex};
1✔
844
    _format_storage_callbacks.unsubscribe(handle);
1✔
845
}
1✔
846

847
CameraServer::Result
848
CameraServerImpl::respond_format_storage(CameraServer::CameraFeedback format_storage_feedback)
1✔
849
{
850
    std::lock_guard<std::mutex> lg{_mutex};
1✔
851

852
    switch (format_storage_feedback) {
1✔
UNCOV
853
        default:
×
854
            // Fallthrough
855
        case CameraServer::CameraFeedback::Unknown:
UNCOV
856
            return CameraServer::Result::Error;
×
857
        case CameraServer::CameraFeedback::Ok: {
1✔
858
            auto command_ack = _server_component_impl->make_command_ack_message(
1✔
859
                _last_format_storage_command, MAV_RESULT_ACCEPTED);
1✔
860
            _server_component_impl->send_command_ack(command_ack);
1✔
861
            return CameraServer::Result::Success;
1✔
862
        }
UNCOV
863
        case CameraServer::CameraFeedback::Busy: {
×
UNCOV
864
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
865
                _last_format_storage_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
866
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
867
            return CameraServer::Result::Success;
×
868
        }
UNCOV
869
        case CameraServer::CameraFeedback::Failed: {
×
UNCOV
870
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
871
                _last_format_storage_command, MAV_RESULT_FAILED);
×
UNCOV
872
            _server_component_impl->send_command_ack(command_ack);
×
873
            return CameraServer::Result::Success;
×
874
        }
875
    }
876
}
1✔
877

878
CameraServer::ResetSettingsHandle
879
CameraServerImpl::subscribe_reset_settings(const CameraServer::ResetSettingsCallback& callback)
1✔
880
{
881
    std::lock_guard<std::mutex> lg{_mutex};
1✔
882
    return _reset_settings_callbacks.subscribe(callback);
1✔
883
}
1✔
884

885
void CameraServerImpl::unsubscribe_reset_settings(CameraServer::ResetSettingsHandle handle)
×
886
{
887
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
888
    _reset_settings_callbacks.unsubscribe(handle);
×
889
}
×
890

891
CameraServer::Result
892
CameraServerImpl::respond_reset_settings(CameraServer::CameraFeedback reset_settings_feedback)
1✔
893
{
894
    std::lock_guard<std::mutex> lg{_mutex};
1✔
895

896
    switch (reset_settings_feedback) {
1✔
UNCOV
897
        default:
×
898
            // Fallthrough
899
        case CameraServer::CameraFeedback::Unknown:
UNCOV
900
            return CameraServer::Result::Error;
×
901
        case CameraServer::CameraFeedback::Ok: {
1✔
902
            auto command_ack = _server_component_impl->make_command_ack_message(
1✔
903
                _last_reset_settings_command, MAV_RESULT_ACCEPTED);
1✔
904
            _server_component_impl->send_command_ack(command_ack);
1✔
905
            return CameraServer::Result::Success;
1✔
906
        }
907
        case CameraServer::CameraFeedback::Busy: {
×
908
            auto command_ack = _server_component_impl->make_command_ack_message(
×
909
                _last_reset_settings_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
910
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
911
            return CameraServer::Result::Success;
×
912
        }
UNCOV
913
        case CameraServer::CameraFeedback::Failed: {
×
UNCOV
914
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
915
                _last_reset_settings_command, MAV_RESULT_FAILED);
×
UNCOV
916
            _server_component_impl->send_command_ack(command_ack);
×
917
            return CameraServer::Result::Success;
×
918
        }
919
    }
920
}
1✔
921

UNCOV
922
CameraServer::TrackingPointCommandHandle CameraServerImpl::subscribe_tracking_point_command(
×
923
    const CameraServer::TrackingPointCommandCallback& callback)
924
{
UNCOV
925
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
926
    return _tracking_point_callbacks.subscribe(callback);
×
927
}
×
928

929
void CameraServerImpl::unsubscribe_tracking_point_command(
×
930
    CameraServer::TrackingPointCommandHandle handle)
931
{
UNCOV
932
    std::lock_guard<std::mutex> lg{_mutex};
×
933
    _tracking_point_callbacks.unsubscribe(handle);
×
934
}
×
935

936
CameraServer::Result CameraServerImpl::respond_tracking_point_command(
×
937
    CameraServer::CameraFeedback tracking_point_feedback)
938
{
UNCOV
939
    std::lock_guard<std::mutex> lg{_mutex};
×
940

UNCOV
941
    switch (tracking_point_feedback) {
×
942
        default:
×
943
            // Fallthrough
944
        case CameraServer::CameraFeedback::Unknown:
945
            return CameraServer::Result::Error;
×
946
        case CameraServer::CameraFeedback::Ok: {
×
947
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
948
                _last_track_point_command, MAV_RESULT_ACCEPTED);
×
949
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
950
            break;
×
951
        }
952
        case CameraServer::CameraFeedback::Busy: {
×
953
            auto command_ack = _server_component_impl->make_command_ack_message(
×
954
                _last_track_point_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
955
            _server_component_impl->send_command_ack(command_ack);
×
956
            return CameraServer::Result::Success;
×
957
        }
UNCOV
958
        case CameraServer::CameraFeedback::Failed: {
×
959
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
960
                _last_track_point_command, MAV_RESULT_FAILED);
×
961
            _server_component_impl->send_command_ack(command_ack);
×
962
            return CameraServer::Result::Success;
×
963
        }
964
    }
965
    return CameraServer::Result::Success;
×
966
}
×
967

968
CameraServer::TrackingRectangleCommandHandle CameraServerImpl::subscribe_tracking_rectangle_command(
×
969
    const CameraServer::TrackingRectangleCommandCallback& callback)
970
{
UNCOV
971
    std::lock_guard<std::mutex> lg{_mutex};
×
972
    return _tracking_rectangle_callbacks.subscribe(callback);
×
973
}
×
974

975
void CameraServerImpl::unsubscribe_tracking_rectangle_command(
×
976
    CameraServer::TrackingRectangleCommandHandle handle)
977
{
978
    std::lock_guard<std::mutex> lg{_mutex};
×
979
    _tracking_rectangle_callbacks.unsubscribe(handle);
×
980
}
×
981

982
CameraServer::Result CameraServerImpl::respond_tracking_rectangle_command(
×
983
    CameraServer::CameraFeedback tracking_rectangle_feedback)
984
{
985
    std::lock_guard<std::mutex> lg{_mutex};
×
986

UNCOV
987
    switch (tracking_rectangle_feedback) {
×
988
        default:
×
989
            // Fallthrough
990
        case CameraServer::CameraFeedback::Unknown:
991
            return CameraServer::Result::Error;
×
992
        case CameraServer::CameraFeedback::Ok: {
×
993
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
994
                _last_track_rectangle_command, MAV_RESULT_ACCEPTED);
×
995
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
996
            break;
×
997
        }
998
        case CameraServer::CameraFeedback::Busy: {
×
999
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1000
                _last_track_rectangle_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
1001
            _server_component_impl->send_command_ack(command_ack);
×
1002
            return CameraServer::Result::Success;
×
1003
        }
UNCOV
1004
        case CameraServer::CameraFeedback::Failed: {
×
1005
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1006
                _last_track_rectangle_command, MAV_RESULT_FAILED);
×
1007
            _server_component_impl->send_command_ack(command_ack);
×
1008
            return CameraServer::Result::Success;
×
1009
        }
1010
    }
1011
    return CameraServer::Result::Success;
×
1012
}
×
1013

1014
CameraServer::TrackingOffCommandHandle CameraServerImpl::subscribe_tracking_off_command(
×
1015
    const CameraServer::TrackingOffCommandCallback& callback)
1016
{
UNCOV
1017
    std::lock_guard<std::mutex> lg{_mutex};
×
1018
    return _tracking_off_callbacks.subscribe(callback);
×
1019
}
×
1020

1021
void CameraServerImpl::unsubscribe_tracking_off_command(
×
1022
    CameraServer::TrackingOffCommandHandle handle)
1023
{
1024
    std::lock_guard<std::mutex> lg{_mutex};
×
1025
    _tracking_off_callbacks.unsubscribe(handle);
×
1026
}
×
1027

1028
CameraServer::Result
UNCOV
1029
CameraServerImpl::respond_tracking_off_command(CameraServer::CameraFeedback tracking_off_feedback)
×
1030
{
1031
    std::lock_guard<std::mutex> lg{_mutex};
×
1032

UNCOV
1033
    switch (tracking_off_feedback) {
×
1034
        default:
×
1035
            // Fallthrough
1036
        case CameraServer::CameraFeedback::Unknown:
1037
            return CameraServer::Result::Error;
×
1038
        case CameraServer::CameraFeedback::Ok: {
×
1039
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1040
                _last_tracking_off_command, MAV_RESULT_ACCEPTED);
×
1041
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
1042
            break;
×
1043
        }
1044
        case CameraServer::CameraFeedback::Busy: {
×
1045
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1046
                _last_tracking_off_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
1047
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
1048
            return CameraServer::Result::Success;
×
1049
        }
UNCOV
1050
        case CameraServer::CameraFeedback::Failed: {
×
1051
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1052
                _last_tracking_off_command, MAV_RESULT_FAILED);
×
1053
            _server_component_impl->send_command_ack(command_ack);
×
1054
            return CameraServer::Result::Success;
×
1055
        }
1056
    }
1057
    return CameraServer::Result::Success;
×
1058
}
×
1059

1060
void CameraServerImpl::start_image_capture_interval(float interval_s, int32_t count, int32_t index)
1✔
1061
{
1062
    // If count == 0, it means capture "forever" until a stop command is received.
1063
    auto remaining = std::make_shared<int32_t>(count == 0 ? INT32_MAX : count);
1✔
1064

1065
    _last_interval_index = index;
1✔
1066

1067
    _image_capture_timer_cookie = _server_component_impl->add_call_every(
1✔
1068
        [this, remaining]() {
15✔
1069
            LogDebug() << "capture image timer triggered";
3✔
1070

1071
            if (!_take_photo_callbacks.empty()) {
3✔
1072
                _take_photo_callbacks.queue(_last_interval_index++, [this](const auto& func) {
3✔
1073
                    _server_component_impl->call_user_callback(func);
3✔
1074
                });
3✔
1075
                (*remaining)--;
3✔
1076
            }
1077

1078
            if (*remaining == 0) {
3✔
UNCOV
1079
                stop_image_capture_interval();
×
1080
            }
1081
        },
3✔
1082
        interval_s);
1083

1084
    _is_image_capture_interval_set = true;
1✔
1085
    _image_capture_timer_interval_s = interval_s;
1✔
1086
}
1✔
1087

1088
void CameraServerImpl::stop_image_capture_interval()
12✔
1089
{
1090
    _server_component_impl->remove_call_every(_image_capture_timer_cookie);
12✔
1091

1092
    std::lock_guard<std::mutex> lg{_mutex};
12✔
1093
    _is_image_capture_interval_set = false;
12✔
1094
    _image_capture_timer_interval_s = 0;
12✔
1095
}
12✔
1096

UNCOV
1097
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_information_request(
×
1098
    const MavlinkCommandReceiver::CommandLong& command)
1099
{
UNCOV
1100
    LogDebug() << "Camera info request";
×
1101

UNCOV
1102
    if (static_cast<int>(command.params.param1) == 0) {
×
UNCOV
1103
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1104
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1105
    }
1106

UNCOV
1107
    return send_camera_information(command);
×
1108
}
1109

1110
std::optional<mavlink_command_ack_t>
1111
CameraServerImpl::process_request_message(const MavlinkCommandReceiver::CommandLong& command)
97✔
1112
{
1113
    switch (static_cast<int>(command.params.param1)) {
97✔
1114
        case MAVLINK_MSG_ID_CAMERA_INFORMATION:
9✔
1115
            return send_camera_information(command);
9✔
1116

1117
        case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS:
9✔
1118
            send_capture_status();
9✔
1119
            return _server_component_impl->make_command_ack_message(
18✔
1120
                command, MAV_RESULT::MAV_RESULT_ACCEPTED);
18✔
1121

1122
        default:
79✔
1123
            LogWarn() << "Got unknown request message!";
79✔
1124
            return _server_component_impl->make_command_ack_message(
158✔
1125
                command, MAV_RESULT::MAV_RESULT_DENIED);
158✔
1126
    }
1127
}
1128

1129
std::optional<mavlink_command_ack_t>
1130
CameraServerImpl::send_camera_information(const MavlinkCommandReceiver::CommandLong& command)
9✔
1131
{
1132
    std::lock_guard<std::mutex> lg{_mutex};
9✔
1133

1134
    if (!_is_information_set) {
9✔
UNCOV
1135
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1136
            command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED);
×
1137
    }
1138

1139
    // ack needs to be sent before camera information message
1140
    auto command_ack =
9✔
1141
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
9✔
1142
    _server_component_impl->send_command_ack(command_ack);
9✔
1143

1144
    // It is safe to ignore the return value of parse_version_string() here
1145
    // since the string was already validated in set_information().
1146
    uint32_t firmware_version;
9✔
1147
    parse_version_string(_information.firmware_version, firmware_version);
9✔
1148

1149
    // capability flags are determined by subscriptions
1150
    uint32_t capability_flags{};
9✔
1151

1152
    if (!_take_photo_callbacks.empty()) {
9✔
1153
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE;
2✔
1154
    }
1155

1156
    if (!_start_video_callbacks.empty()) {
9✔
UNCOV
1157
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
×
1158
    }
1159

1160
    if (!_set_mode_callbacks.empty()) {
9✔
1161
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES;
2✔
1162
    }
1163

1164
    if (_information.image_in_video_mode_supported) {
9✔
UNCOV
1165
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE;
×
1166
    }
1167

1168
    if (_information.video_in_image_mode_supported) {
9✔
UNCOV
1169
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE;
×
1170
    }
1171

1172
    if (_is_video_streaming_set) {
9✔
1173
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM;
1✔
1174
    }
1175

1176
    if (!_tracking_point_callbacks.empty()) {
9✔
1177
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT;
×
1178
    }
1179

1180
    if (!_tracking_rectangle_callbacks.empty()) {
9✔
UNCOV
1181
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE;
×
1182
    }
1183

1184
    if (!_zoom_range_callbacks.empty() || !_zoom_in_start_callbacks.empty() ||
18✔
1185
        !_zoom_out_start_callbacks.empty()) {
9✔
UNCOV
1186
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM;
×
1187
    }
1188

1189
    _information.vendor_name.resize(sizeof(mavlink_camera_information_t::vendor_name));
9✔
1190
    _information.model_name.resize(sizeof(mavlink_camera_information_t::model_name));
9✔
1191
    _information.definition_file_uri.resize(
9✔
1192
        sizeof(mavlink_camera_information_t::cam_definition_uri));
1193

1194
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
9✔
1195
        mavlink_message_t message{};
9✔
1196
        mavlink_msg_camera_information_pack_chan(
27✔
1197
            mavlink_address.system_id,
9✔
1198
            mavlink_address.component_id,
9✔
1199
            channel,
1200
            &message,
1201
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
18✔
1202
            reinterpret_cast<const uint8_t*>(_information.vendor_name.c_str()),
9✔
1203
            reinterpret_cast<const uint8_t*>(_information.model_name.c_str()),
9✔
1204
            firmware_version,
9✔
1205
            _information.focal_length_mm,
1206
            _information.horizontal_sensor_size_mm,
1207
            _information.vertical_sensor_size_mm,
1208
            _information.horizontal_resolution_px,
9✔
1209
            _information.vertical_resolution_px,
9✔
1210
            _information.lens_id,
9✔
1211
            capability_flags,
9✔
1212
            _information.definition_file_version,
9✔
1213
            _information.definition_file_uri.c_str(),
1214
            0,
1215
            0);
1216
        return message;
9✔
1217
    });
1218

1219
    return std::nullopt;
9✔
1220
}
9✔
1221

1222
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_settings_request(
9✔
1223
    const MavlinkCommandReceiver::CommandLong& command)
1224
{
1225
    auto settings = static_cast<bool>(command.params.param1);
9✔
1226

1227
    if (!settings) {
9✔
UNCOV
1228
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1229
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1230
    }
1231

1232
    // ack needs to be sent before camera information message
1233
    auto command_ack =
9✔
1234
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
9✔
1235
    _server_component_impl->send_command_ack(command_ack);
9✔
1236
    LogDebug() << "sent settings ack";
9✔
1237

1238
    // unsupported
1239
    const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE;
9✔
1240
    const float zoom_level = 0;
9✔
1241
    const float focus_level = 0;
9✔
1242

1243
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
9✔
1244
        mavlink_message_t message{};
9✔
1245
        mavlink_msg_camera_settings_pack_chan(
18✔
1246
            mavlink_address.system_id,
9✔
1247
            mavlink_address.component_id,
9✔
1248
            channel,
1249
            &message,
1250
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
9✔
1251
            mode_id,
1252
            zoom_level,
9✔
1253
            focus_level,
9✔
1254
            0);
1255
        return message;
9✔
1256
    });
1257
    LogDebug() << "sent settings msg";
9✔
1258

1259
    // ack was already sent
1260
    return std::nullopt;
9✔
1261
}
1262

1263
std::optional<mavlink_command_ack_t> CameraServerImpl::process_storage_information_request(
16✔
1264
    const MavlinkCommandReceiver::CommandLong& command)
1265
{
1266
    auto storage_id = static_cast<uint8_t>(command.params.param1);
16✔
1267
    auto information = static_cast<bool>(command.params.param2);
16✔
1268

1269
    if (!information) {
16✔
UNCOV
1270
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1271
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1272
    }
1273

1274
    std::lock_guard<std::mutex> lg{_mutex};
16✔
1275

1276
    if (_storage_information_callbacks.empty()) {
16✔
1277
        LogDebug()
28✔
1278
            << "Get storage information requested with no set storage information subscriber";
28✔
1279
        return _server_component_impl->make_command_ack_message(
28✔
1280
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
28✔
1281
    }
1282

1283
    // TODO may need support multi storage id
1284
    _last_storage_id = storage_id;
2✔
1285

1286
    _last_storage_information_command = command;
2✔
1287

1288
    _storage_information_callbacks.queue(
2✔
1289
        storage_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
2✔
1290

1291
    // ack will be sent later in respond_storage_information
1292
    return std::nullopt;
2✔
1293
}
16✔
1294

1295
std::optional<mavlink_command_ack_t>
1296
CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLong& command)
1✔
1297
{
1298
    auto storage_id = static_cast<uint8_t>(command.params.param1);
1✔
1299
    auto format = static_cast<bool>(command.params.param2);
1✔
1300
    auto reset_image_log = static_cast<bool>(command.params.param3);
1✔
1301

1302
    UNUSED(format);
1✔
1303
    UNUSED(reset_image_log);
1✔
1304

1305
    std::lock_guard<std::mutex> lg{_mutex};
1✔
1306

1307
    if (_format_storage_callbacks.empty()) {
1✔
UNCOV
1308
        LogDebug() << "process storage format requested with no storage format subscriber";
×
UNCOV
1309
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1310
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1311
    }
1312

1313
    _last_format_storage_command = command;
1✔
1314

1315
    _format_storage_callbacks.queue(
1✔
1316
        storage_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
1✔
1317

1318
    return std::nullopt;
1✔
1319
}
1✔
1320

UNCOV
1321
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_capture_status_request(
×
1322
    const MavlinkCommandReceiver::CommandLong& command)
1323
{
UNCOV
1324
    auto capture_status = static_cast<bool>(command.params.param1);
×
1325

UNCOV
1326
    if (!capture_status) {
×
UNCOV
1327
        return _server_component_impl->make_command_ack_message(
×
1328
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1329
    }
1330

UNCOV
1331
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1332
    if (_capture_status_callbacks.empty()) {
×
UNCOV
1333
        LogDebug() << "process camera capture status requested with no capture status subscriber";
×
UNCOV
1334
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1335
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1336
    }
1337

UNCOV
1338
    _last_capture_status_command = command;
×
1339

1340
    // may not need param for now ,just use zero
1341
    _capture_status_callbacks.queue(
×
UNCOV
1342
        0, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1343

1344
    // ack was already sent
UNCOV
1345
    return std::nullopt;
×
1346
}
×
1347

1348
void CameraServerImpl::send_capture_status()
13✔
1349
{
1350
    std::lock_guard<std::mutex> lg{_mutex};
13✔
1351

1352
    uint8_t image_status{};
13✔
1353
    if (_capture_status.image_status ==
13✔
1354
            CameraServer::CaptureStatus::ImageStatus::CaptureInProgress ||
13✔
1355
        _capture_status.image_status ==
13✔
1356
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress) {
UNCOV
1357
        image_status |= StatusFlags::IN_PROGRESS;
×
1358
    }
1359

1360
    if (_capture_status.image_status == CameraServer::CaptureStatus::ImageStatus::IntervalIdle ||
13✔
1361
        _capture_status.image_status ==
13✔
1362
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress ||
13✔
1363
        _is_image_capture_interval_set) {
13✔
1364
        image_status |= StatusFlags::INTERVAL_SET;
3✔
1365
    }
1366

1367
    uint8_t video_status = 0;
13✔
1368
    if (_capture_status.video_status == CameraServer::CaptureStatus::VideoStatus::Idle) {
13✔
1369
        video_status = 0;
13✔
UNCOV
1370
    } else if (
×
UNCOV
1371
        _capture_status.video_status ==
×
1372
        CameraServer::CaptureStatus::VideoStatus::CaptureInProgress) {
UNCOV
1373
        video_status = 1;
×
1374
    }
1375

1376
    const uint32_t recording_time_ms =
13✔
1377
        static_cast<uint32_t>(static_cast<double>(_capture_status.recording_time_s) * 1e3);
13✔
1378
    const float available_capacity = _capture_status.available_capacity_mib;
13✔
1379

1380
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
13✔
1381
        mavlink_message_t message{};
13✔
1382
        mavlink_msg_camera_capture_status_pack_chan(
26✔
1383
            mavlink_address.system_id,
13✔
1384
            mavlink_address.component_id,
13✔
1385
            channel,
1386
            &message,
1387
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
13✔
1388
            image_status,
13✔
1389
            video_status,
13✔
1390
            _image_capture_timer_interval_s,
1391
            recording_time_ms,
13✔
1392
            available_capacity,
13✔
1393
            _image_capture_count,
1394
            0);
1395
        return message;
13✔
1396
    });
1397
}
13✔
1398

1399
std::optional<mavlink_command_ack_t>
1400
CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::CommandLong& command)
1✔
1401
{
1402
    auto reset = static_cast<bool>(command.params.param1);
1✔
1403

1404
    UNUSED(reset);
1✔
1405

1406
    std::lock_guard<std::mutex> lg{_mutex};
1✔
1407

1408
    if (_reset_settings_callbacks.empty()) {
1✔
UNCOV
1409
        LogDebug() << "reset camera settings requested with no camera settings subscriber";
×
UNCOV
1410
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1411
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1412
    }
1413

1414
    _last_reset_settings_command = command;
1✔
1415
    _reset_settings_callbacks.queue(
1✔
1416
        0, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
1✔
1417

1418
    return std::nullopt;
1✔
1419
}
1✔
1420

1421
std::optional<mavlink_command_ack_t>
1422
CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandLong& command)
2✔
1423
{
1424
    auto camera_mode = static_cast<CAMERA_MODE>(command.params.param2);
2✔
1425

1426
    std::lock_guard<std::mutex> lg{_mutex};
2✔
1427

1428
    if (_set_mode_callbacks.empty()) {
2✔
1429
        LogDebug() << "Set mode requested with no set mode subscriber";
×
1430
        return _server_component_impl->make_command_ack_message(
×
1431
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1432
    }
1433

1434
    // convert camera mode enum type
1435
    CameraServer::Mode convert_camera_mode = CameraServer::Mode::Unknown;
2✔
1436
    if (camera_mode == CAMERA_MODE_IMAGE) {
2✔
1437
        convert_camera_mode = CameraServer::Mode::Photo;
1✔
1438
    } else if (camera_mode == CAMERA_MODE_VIDEO) {
1✔
1439
        convert_camera_mode = CameraServer::Mode::Video;
1✔
1440
    }
1441

1442
    if (convert_camera_mode == CameraServer::Mode::Unknown) {
2✔
UNCOV
1443
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1444
            command, MAV_RESULT::MAV_RESULT_DENIED);
×
1445
    }
1446

1447
    _last_set_mode_command = command;
2✔
1448

1449
    _set_mode_callbacks.queue(convert_camera_mode, [this](const auto& func) {
2✔
1450
        _server_component_impl->call_user_callback(func);
2✔
1451
    });
2✔
1452

1453
    return std::nullopt;
2✔
1454
}
2✔
1455

1456
std::optional<mavlink_command_ack_t>
UNCOV
1457
CameraServerImpl::process_set_camera_zoom(const MavlinkCommandReceiver::CommandLong& command)
×
1458
{
UNCOV
1459
    auto zoom_type = static_cast<CAMERA_ZOOM_TYPE>(command.params.param1);
×
UNCOV
1460
    auto zoom_value = command.params.param2;
×
1461

UNCOV
1462
    std::lock_guard<std::mutex> lg{_mutex};
×
1463

1464
    if (_zoom_in_start_callbacks.empty() && _zoom_out_start_callbacks.empty() &&
×
UNCOV
1465
        _zoom_stop_callbacks.empty() && _zoom_range_callbacks.empty()) {
×
UNCOV
1466
        LogWarn() << "No camera zoom is supported";
×
UNCOV
1467
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1468
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1469
    }
1470

UNCOV
1471
    auto unsupported = [&]() {
×
UNCOV
1472
        LogWarn() << "unsupported set camera zoom type (" << (int)zoom_type << ") request";
×
UNCOV
1473
    };
×
1474

UNCOV
1475
    switch (zoom_type) {
×
UNCOV
1476
        case ZOOM_TYPE_CONTINUOUS:
×
1477
            if (zoom_value == -1.f) {
×
UNCOV
1478
                if (_zoom_out_start_callbacks.empty()) {
×
1479
                    unsupported();
×
1480
                    return _server_component_impl->make_command_ack_message(
×
UNCOV
1481
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1482
                } else {
UNCOV
1483
                    _last_zoom_out_start_command = command;
×
1484
                    int dummy = 0;
×
1485
                    _zoom_out_start_callbacks.queue(dummy, [this](const auto& func) {
×
1486
                        _server_component_impl->call_user_callback(func);
×
1487
                    });
×
1488
                }
UNCOV
1489
            } else if (zoom_value == 1.f) {
×
UNCOV
1490
                if (_zoom_in_start_callbacks.empty()) {
×
1491
                    unsupported();
×
1492
                    return _server_component_impl->make_command_ack_message(
×
1493
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1494
                } else {
1495
                    _last_zoom_in_start_command = command;
×
1496
                    int dummy = 0;
×
1497
                    _zoom_in_start_callbacks.queue(dummy, [this](const auto& func) {
×
1498
                        _server_component_impl->call_user_callback(func);
×
1499
                    });
×
1500
                }
1501
            } else if (zoom_value == 0.f) {
×
UNCOV
1502
                if (_zoom_stop_callbacks.empty()) {
×
1503
                    unsupported();
×
1504
                    return _server_component_impl->make_command_ack_message(
×
1505
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1506
                } else {
1507
                    _last_zoom_stop_command = command;
×
UNCOV
1508
                    int dummy = 0;
×
1509
                    _zoom_stop_callbacks.queue(dummy, [this](const auto& func) {
×
1510
                        _server_component_impl->call_user_callback(func);
×
1511
                    });
×
1512
                }
1513
            } else {
UNCOV
1514
                LogWarn() << "Invalid zoom value";
×
1515
                return _server_component_impl->make_command_ack_message(
×
1516
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1517
            }
1518
            break;
×
1519
        case ZOOM_TYPE_RANGE:
×
UNCOV
1520
            if (_zoom_range_callbacks.empty()) {
×
1521
                unsupported();
×
1522
                return _server_component_impl->make_command_ack_message(
×
1523
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1524

1525
            } else {
UNCOV
1526
                _last_zoom_range_command = command;
×
1527
                _zoom_range_callbacks.queue(zoom_value, [this](const auto& func) {
×
1528
                    _server_component_impl->call_user_callback(func);
×
1529
                });
×
1530
            }
1531
            break;
×
UNCOV
1532
        case ZOOM_TYPE_STEP:
×
1533
        // Fallthrough
1534
        case ZOOM_TYPE_FOCAL_LENGTH:
1535
        // Fallthrough
1536
        case ZOOM_TYPE_HORIZONTAL_FOV:
1537
        // Fallthrough
1538
        default:
1539
            unsupported();
×
1540
            return _server_component_impl->make_command_ack_message(
×
1541
                command, MAV_RESULT::MAV_RESULT_DENIED);
×
1542
            break;
1543
    }
1544

1545
    // For any success so far, we don't ack yet, but later when the respond function is called.
1546
    return std::nullopt;
×
1547
}
×
1548

1549
std::optional<mavlink_command_ack_t>
UNCOV
1550
CameraServerImpl::process_set_camera_focus(const MavlinkCommandReceiver::CommandLong& command)
×
1551
{
1552
    auto focus_type = static_cast<SET_FOCUS_TYPE>(command.params.param1);
×
UNCOV
1553
    auto focus_value = command.params.param2;
×
1554

UNCOV
1555
    UNUSED(focus_type);
×
UNCOV
1556
    UNUSED(focus_value);
×
1557

UNCOV
1558
    LogDebug() << "unsupported set camera focus request";
×
1559

1560
    return _server_component_impl->make_command_ack_message(
×
1561
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1562
}
1563

1564
std::optional<mavlink_command_ack_t>
UNCOV
1565
CameraServerImpl::process_set_storage_usage(const MavlinkCommandReceiver::CommandLong& command)
×
1566
{
1567
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
UNCOV
1568
    auto usage = static_cast<STORAGE_USAGE_FLAG>(command.params.param2);
×
1569

1570
    UNUSED(storage_id);
×
UNCOV
1571
    UNUSED(usage);
×
1572

1573
    LogDebug() << "unsupported set storage usage request";
×
1574

1575
    return _server_component_impl->make_command_ack_message(
×
1576
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1577
}
1578

1579
std::optional<mavlink_command_ack_t>
1580
CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command)
2✔
1581
{
1582
    auto interval_s = command.params.param2;
2✔
1583
    auto total_images = static_cast<int32_t>(command.params.param3);
2✔
1584
    auto seq_number = static_cast<int32_t>(command.params.param4);
2✔
1585

1586
    LogDebug() << "received image start capture request - interval: " << +interval_s
6✔
1587
               << " total: " << +total_images << " index: " << +seq_number;
6✔
1588

1589
    // TODO: validate parameters and return MAV_RESULT_DENIED not valid
1590

1591
    stop_image_capture_interval();
2✔
1592

1593
    std::lock_guard<std::mutex> lg{_mutex};
2✔
1594

1595
    if (_take_photo_callbacks.empty()) {
2✔
1596
        LogDebug() << "image capture requested with no take photo subscriber";
×
UNCOV
1597
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1598
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1599
    }
1600

1601
    // single image capture
1602
    if (total_images == 1) {
2✔
1603
        // MAV_RESULT_ACCEPTED must be sent before CAMERA_IMAGE_CAPTURED
1604
        auto command_ack = _server_component_impl->make_command_ack_message(
1✔
1605
            command, MAV_RESULT::MAV_RESULT_IN_PROGRESS);
1606
        _server_component_impl->send_command_ack(command_ack);
1✔
1607

1608
        _last_take_photo_command = command;
1✔
1609

1610
        _take_photo_callbacks.queue(seq_number, [this](const auto& func) {
1✔
1611
            _server_component_impl->call_user_callback(func);
1✔
1612
        });
1✔
1613

1614
        return std::nullopt;
1✔
1615
    }
1616

1617
    start_image_capture_interval(interval_s, total_images, seq_number);
1✔
1618

1619
    return _server_component_impl->make_command_ack_message(
2✔
1620
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
2✔
1621
}
2✔
1622

1623
std::optional<mavlink_command_ack_t>
1624
CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
1✔
1625
{
1626
    LogDebug() << "received image stop capture request";
1✔
1627

1628
    // REVISIT: should we return something other that MAV_RESULT_ACCEPTED if
1629
    // there is not currently a capture interval active?
1630
    stop_image_capture_interval();
1✔
1631

1632
    return _server_component_impl->make_command_ack_message(
2✔
1633
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
2✔
1634
}
1635

UNCOV
1636
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_image_capture_request(
×
1637
    const MavlinkCommandReceiver::CommandLong& command)
1638
{
UNCOV
1639
    auto seq_number = static_cast<uint32_t>(command.params.param1);
×
1640

UNCOV
1641
    UNUSED(seq_number);
×
1642

UNCOV
1643
    LogDebug() << "unsupported image capture request";
×
1644

UNCOV
1645
    return _server_component_impl->make_command_ack_message(
×
UNCOV
1646
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1647
}
1648

1649
std::optional<mavlink_command_ack_t>
UNCOV
1650
CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1651
{
UNCOV
1652
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
UNCOV
1653
    auto status_frequency = command.params.param2;
×
1654

UNCOV
1655
    UNUSED(status_frequency);
×
1656

UNCOV
1657
    std::lock_guard<std::mutex> lg{_mutex};
×
1658

1659
    if (_start_video_callbacks.empty()) {
×
UNCOV
1660
        LogDebug() << "video start capture requested with no video start capture subscriber";
×
1661
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1662
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1663
    }
1664

1665
    _last_start_video_command = command;
×
1666
    _start_video_callbacks.queue(
×
UNCOV
1667
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1668

UNCOV
1669
    return std::nullopt;
×
1670
}
×
1671

1672
std::optional<mavlink_command_ack_t>
1673
CameraServerImpl::process_video_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1674
{
1675
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1676

1677
    std::lock_guard<std::mutex> lg{_mutex};
×
1678

1679
    if (_stop_video_callbacks.empty()) {
×
1680
        LogDebug() << "video stop capture requested with no video stop capture subscriber";
×
1681
        return _server_component_impl->make_command_ack_message(
×
1682
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1683
    }
1684

1685
    _last_stop_video_command = command;
×
1686
    _stop_video_callbacks.queue(
×
1687
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1688

1689
    return std::nullopt;
×
1690
}
×
1691

1692
std::optional<mavlink_command_ack_t>
1693
CameraServerImpl::process_video_start_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1694
{
1695
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1696

1697
    std::lock_guard<std::mutex> lg{_mutex};
×
1698

1699
    if (_start_video_streaming_callbacks.empty()) {
×
1700
        LogDebug() << "video start streaming requested with no video start streaming subscriber";
×
1701
        return _server_component_impl->make_command_ack_message(
×
1702
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1703
    }
1704

1705
    _last_start_video_streaming_command = command;
×
1706
    _start_video_streaming_callbacks.queue(
×
1707
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1708

1709
    return std::nullopt;
×
1710
}
×
1711

1712
std::optional<mavlink_command_ack_t>
1713
CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1714
{
1715
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1716

1717
    std::lock_guard<std::mutex> lg{_mutex};
×
1718

1719
    if (_stop_video_streaming_callbacks.empty()) {
×
1720
        LogDebug() << "video stop streaming requested with no video stop streaming subscriber";
×
1721
        return _server_component_impl->make_command_ack_message(
×
1722
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1723
    }
1724

1725
    _last_stop_video_streaming_command = command;
×
1726
    _stop_video_streaming_callbacks.queue(
×
1727
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1728

1729
    return std::nullopt;
×
1730
}
×
1731

1732
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_information_request(
15✔
1733
    const MavlinkCommandReceiver::CommandLong& command)
1734
{
1735
    auto stream_id = static_cast<uint8_t>(command.params.param1);
15✔
1736

1737
    UNUSED(stream_id);
15✔
1738

1739
    std::lock_guard<std::mutex> lg{_mutex};
15✔
1740

1741
    if (_is_video_streaming_set) {
15✔
1742
        auto command_ack = _server_component_impl->make_command_ack_message(
1✔
1743
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
1744
        _server_component_impl->send_command_ack(command_ack);
1✔
1745
        LogDebug() << "sent video streaming ack";
1✔
1746

1747
        const char name[32] = "";
1✔
1748

1749
        _video_streaming.rtsp_uri.resize(sizeof(mavlink_video_stream_information_t::uri));
1✔
1750

1751
        mavlink_message_t msg{};
1✔
1752
        mavlink_msg_video_stream_information_pack(
2✔
1753
            _server_component_impl->get_own_system_id(),
1✔
1754
            _server_component_impl->get_own_component_id(),
1✔
1755
            &msg,
1756
            0, // Stream id
1757
            0, // Count
1758
            VIDEO_STREAM_TYPE_RTSP,
1759
            VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1760
            0, // famerate
1761
            0, // resolution horizontal
1762
            0, // resolution vertical
1763
            0, // bitrate
1764
            0, // rotation
1765
            0, // horizontal field of view
1766
            name,
1767
            _video_streaming.rtsp_uri.c_str(),
1768
            0,
1769
            0);
1770

1771
        _server_component_impl->send_message(msg);
1✔
1772

1773
        // Ack already sent.
1774
        return std::nullopt;
1✔
1775

1776
    } else {
1777
        return _server_component_impl->make_command_ack_message(
28✔
1778
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
28✔
1779
    }
1780
}
15✔
1781

1782
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_status_request(
17✔
1783
    const MavlinkCommandReceiver::CommandLong& command)
1784
{
1785
    auto stream_id = static_cast<uint8_t>(command.params.param1);
17✔
1786

1787
    UNUSED(stream_id);
17✔
1788

1789
    std::lock_guard<std::mutex> lg{_mutex};
17✔
1790

1791
    if (!_is_video_streaming_set) {
17✔
1792
        return _server_component_impl->make_command_ack_message(
32✔
1793
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
32✔
1794
    }
1795

1796
    auto command_ack =
1✔
1797
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
1✔
1798
    _server_component_impl->send_command_ack(command_ack);
1✔
1799
    LogDebug() << "sent video streaming ack";
1✔
1800

1801
    mavlink_message_t msg{};
1✔
1802
    mavlink_msg_video_stream_status_pack(
1✔
1803
        _server_component_impl->get_own_system_id(),
1✔
1804
        _server_component_impl->get_own_component_id(),
1✔
1805
        &msg,
1806
        0, // Stream id
1807
        VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1808
        0, // framerate
1809
        0, // resolution horizontal
1810
        0, // resolution vertical
1811
        0, // bitrate
1812
        0, // rotation
1813
        0, // horizontal field of view
1814
        0);
1815
    _server_component_impl->send_message(msg);
1✔
1816

1817
    // ack was already sent
1818
    return std::nullopt;
1✔
1819
}
17✔
1820

1821
CameraServer::ZoomInStartHandle
UNCOV
1822
CameraServerImpl::subscribe_zoom_in_start(const CameraServer::ZoomInStartCallback& callback)
×
1823
{
UNCOV
1824
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1825
    return _zoom_in_start_callbacks.subscribe(callback);
×
UNCOV
1826
}
×
1827

UNCOV
1828
void CameraServerImpl::unsubscribe_zoom_in_start(CameraServer::ZoomInStartHandle handle)
×
1829
{
UNCOV
1830
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1831
    _zoom_in_start_callbacks.unsubscribe(handle);
×
UNCOV
1832
}
×
1833

1834
CameraServer::Result
UNCOV
1835
CameraServerImpl::respond_zoom_in_start(CameraServer::CameraFeedback zoom_in_start_feedback)
×
1836
{
UNCOV
1837
    std::lock_guard<std::mutex> lg{_mutex};
×
1838

UNCOV
1839
    switch (zoom_in_start_feedback) {
×
UNCOV
1840
        default:
×
1841
            // Fallthrough
1842
        case CameraServer::CameraFeedback::Unknown:
UNCOV
1843
            return CameraServer::Result::Error;
×
1844
        case CameraServer::CameraFeedback::Ok: {
×
1845
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1846
                _last_zoom_in_start_command, MAV_RESULT_ACCEPTED);
×
UNCOV
1847
            _server_component_impl->send_command_ack(command_ack);
×
1848
            return CameraServer::Result::Success;
×
1849
        }
1850
        case CameraServer::CameraFeedback::Busy: {
×
1851
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1852
                _last_zoom_in_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
1853
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
1854
            return CameraServer::Result::Success;
×
1855
        }
UNCOV
1856
        case CameraServer::CameraFeedback::Failed: {
×
1857
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1858
                _last_zoom_in_start_command, MAV_RESULT_FAILED);
×
1859
            _server_component_impl->send_command_ack(command_ack);
×
1860
            return CameraServer::Result::Success;
×
1861
        }
1862
    }
1863
}
×
1864

1865
CameraServer::ZoomOutStartHandle
1866
CameraServerImpl::subscribe_zoom_out_start(const CameraServer::ZoomOutStartCallback& callback)
×
1867
{
1868
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1869
    return _zoom_out_start_callbacks.subscribe(callback);
×
1870
}
×
1871

1872
void CameraServerImpl::unsubscribe_zoom_out_start(CameraServer::ZoomOutStartHandle handle)
×
1873
{
1874
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1875
    _zoom_out_start_callbacks.unsubscribe(handle);
×
1876
}
×
1877

1878
CameraServer::Result
1879
CameraServerImpl::respond_zoom_out_start(CameraServer::CameraFeedback zoom_out_start_feedback)
×
1880
{
UNCOV
1881
    std::lock_guard<std::mutex> lg{_mutex};
×
1882

1883
    switch (zoom_out_start_feedback) {
×
UNCOV
1884
        default:
×
1885
            // Fallthrough
1886
        case CameraServer::CameraFeedback::Unknown:
UNCOV
1887
            return CameraServer::Result::Error;
×
1888
        case CameraServer::CameraFeedback::Ok: {
×
1889
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1890
                _last_zoom_out_start_command, MAV_RESULT_ACCEPTED);
×
UNCOV
1891
            _server_component_impl->send_command_ack(command_ack);
×
1892
            return CameraServer::Result::Success;
×
1893
        }
1894
        case CameraServer::CameraFeedback::Busy: {
×
1895
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1896
                _last_zoom_out_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
1897
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
1898
            return CameraServer::Result::Success;
×
1899
        }
UNCOV
1900
        case CameraServer::CameraFeedback::Failed: {
×
1901
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1902
                _last_zoom_out_start_command, MAV_RESULT_FAILED);
×
1903
            _server_component_impl->send_command_ack(command_ack);
×
1904
            return CameraServer::Result::Success;
×
1905
        }
1906
    }
1907
}
×
1908

1909
CameraServer::ZoomStopHandle
1910
CameraServerImpl::subscribe_zoom_stop(const CameraServer::ZoomStopCallback& callback)
×
1911
{
1912
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1913
    return _zoom_stop_callbacks.subscribe(callback);
×
1914
}
×
1915

1916
void CameraServerImpl::unsubscribe_zoom_stop(CameraServer::ZoomStopHandle handle)
×
1917
{
1918
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1919
    _zoom_stop_callbacks.unsubscribe(handle);
×
1920
}
×
1921

1922
CameraServer::Result
1923
CameraServerImpl::respond_zoom_stop(CameraServer::CameraFeedback zoom_stop_feedback)
×
1924
{
UNCOV
1925
    std::lock_guard<std::mutex> lg{_mutex};
×
1926

1927
    switch (zoom_stop_feedback) {
×
UNCOV
1928
        default:
×
1929
            // Fallthrough
1930
        case CameraServer::CameraFeedback::Unknown:
UNCOV
1931
            return CameraServer::Result::Error;
×
1932
        case CameraServer::CameraFeedback::Ok: {
×
1933
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1934
                _last_zoom_stop_command, MAV_RESULT_ACCEPTED);
×
UNCOV
1935
            _server_component_impl->send_command_ack(command_ack);
×
1936
            return CameraServer::Result::Success;
×
1937
        }
1938
        case CameraServer::CameraFeedback::Busy: {
×
1939
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1940
                _last_zoom_stop_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
1941
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
1942
            return CameraServer::Result::Success;
×
1943
        }
UNCOV
1944
        case CameraServer::CameraFeedback::Failed: {
×
1945
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1946
                _last_zoom_stop_command, MAV_RESULT_FAILED);
×
1947
            _server_component_impl->send_command_ack(command_ack);
×
1948
            return CameraServer::Result::Success;
×
1949
        }
1950
    }
1951
}
×
1952

1953
CameraServer::ZoomRangeHandle
1954
CameraServerImpl::subscribe_zoom_range(const CameraServer::ZoomRangeCallback& callback)
×
1955
{
1956
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1957
    return _zoom_range_callbacks.subscribe(callback);
×
1958
}
×
1959

1960
void CameraServerImpl::unsubscribe_zoom_range(CameraServer::ZoomRangeHandle handle)
×
1961
{
1962
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1963
    _zoom_range_callbacks.unsubscribe(handle);
×
1964
}
×
1965

1966
CameraServer::Result
1967
CameraServerImpl::respond_zoom_range(CameraServer::CameraFeedback zoom_range_feedback)
×
1968
{
UNCOV
1969
    std::lock_guard<std::mutex> lg{_mutex};
×
1970

1971
    switch (zoom_range_feedback) {
×
UNCOV
1972
        case CameraServer::CameraFeedback::Ok: {
×
UNCOV
1973
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1974
                _last_zoom_range_command, MAV_RESULT_ACCEPTED);
×
UNCOV
1975
            _server_component_impl->send_command_ack(command_ack);
×
1976
            return CameraServer::Result::Success;
×
1977
        }
1978
        case CameraServer::CameraFeedback::Busy: {
×
UNCOV
1979
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1980
                _last_zoom_range_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
UNCOV
1981
            _server_component_impl->send_command_ack(command_ack);
×
1982
            return CameraServer::Result::Success;
×
1983
        }
1984
        case CameraServer::CameraFeedback::Failed: {
×
UNCOV
1985
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1986
                _last_zoom_range_command, MAV_RESULT_FAILED);
×
1987
            _server_component_impl->send_command_ack(command_ack);
×
UNCOV
1988
            return CameraServer::Result::Success;
×
1989
        }
UNCOV
1990
        case CameraServer::CameraFeedback::Unknown:
×
1991
            // Fallthrough
1992
        default:
1993
            return CameraServer::Result::Error;
×
1994
    }
1995
}
×
1996

1997
std::optional<mavlink_command_ack_t>
1998
CameraServerImpl::process_track_point_command(const MavlinkCommandReceiver::CommandLong& command)
×
1999
{
2000
    if (!is_command_sender_ok(command)) {
×
2001
        LogWarn() << "Incoming track point command is for target sysid "
×
2002
                  << int(command.target_system_id) << " instead of "
×
UNCOV
2003
                  << int(_server_component_impl->get_own_system_id());
×
2004
        return std::nullopt;
×
2005
    }
2006

2007
    std::lock_guard<std::mutex> lg{_mutex};
×
2008

UNCOV
2009
    if (_tracking_point_callbacks.empty()) {
×
2010
        LogDebug() << "Track point requested with no user callback provided";
×
UNCOV
2011
        return _server_component_impl->make_command_ack_message(
×
UNCOV
2012
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
2013
    }
2014

2015
    CameraServer::TrackPoint track_point{
×
UNCOV
2016
        command.params.param1, command.params.param2, command.params.param3};
×
2017

2018
    _last_track_point_command = command;
×
UNCOV
2019
    _tracking_point_callbacks.queue(track_point, [this](const auto& func) {
×
2020
        _server_component_impl->call_user_callback(func);
×
2021
    });
×
2022
    // We don't send an ack but leave that to the user.
2023
    return std::nullopt;
×
2024
}
×
2025

UNCOV
2026
std::optional<mavlink_command_ack_t> CameraServerImpl::process_track_rectangle_command(
×
2027
    const MavlinkCommandReceiver::CommandLong& command)
2028
{
2029
    if (!is_command_sender_ok(command)) {
×
2030
        LogWarn() << "Incoming track rectangle command is for target sysid "
×
2031
                  << int(command.target_system_id) << " instead of "
×
2032
                  << int(_server_component_impl->get_own_system_id());
×
UNCOV
2033
        return std::nullopt;
×
2034
    }
2035

2036
    std::lock_guard<std::mutex> lg{_mutex};
×
2037

2038
    if (_tracking_rectangle_callbacks.empty()) {
×
2039
        LogDebug() << "Track rectangle requested with no user callback provided";
×
2040
        return _server_component_impl->make_command_ack_message(
×
2041
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
2042
    }
2043

2044
    CameraServer::TrackRectangle track_rectangle{
×
UNCOV
2045
        command.params.param1, command.params.param2, command.params.param3, command.params.param4};
×
2046

UNCOV
2047
    _last_track_rectangle_command = command;
×
UNCOV
2048
    _tracking_rectangle_callbacks.queue(track_rectangle, [this](const auto& func) {
×
2049
        _server_component_impl->call_user_callback(func);
×
2050
    });
×
2051
    // We don't send an ack but leave that to the user.
2052
    return std::nullopt;
×
2053
}
×
2054

2055
std::optional<mavlink_command_ack_t>
2056
CameraServerImpl::process_track_off_command(const MavlinkCommandReceiver::CommandLong& command)
×
2057
{
2058
    if (!is_command_sender_ok(command)) {
×
2059
        LogWarn() << "Incoming track off command is for target sysid "
×
2060
                  << int(command.target_system_id) << " instead of "
×
2061
                  << int(_server_component_impl->get_own_system_id());
×
UNCOV
2062
        return std::nullopt;
×
2063
    }
2064

2065
    std::lock_guard<std::mutex> lg{_mutex};
×
2066

2067
    if (_tracking_off_callbacks.empty()) {
×
2068
        LogDebug() << "Tracking off requested with no user callback provided";
×
2069
        return _server_component_impl->make_command_ack_message(
×
2070
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
2071
    }
2072

2073
    _last_tracking_off_command = command;
×
UNCOV
2074
    _tracking_off_callbacks.queue(
×
UNCOV
2075
        0, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
2076
    // We don't send an ack but leave that to the user.
UNCOV
2077
    return std::nullopt;
×
2078
}
×
2079

2080
std::optional<mavlink_command_ack_t>
2081
CameraServerImpl::process_set_message_interval(const MavlinkCommandReceiver::CommandLong& command)
×
2082
{
UNCOV
2083
    if (!is_command_sender_ok(command)) {
×
UNCOV
2084
        LogWarn() << "Incoming track off command is for target sysid "
×
2085
                  << int(command.target_system_id) << " instead of "
×
UNCOV
2086
                  << int(_server_component_impl->get_own_system_id());
×
2087
        return std::nullopt;
×
2088
    }
2089

2090
    auto message_id = static_cast<uint32_t>(command.params.param1);
×
UNCOV
2091
    auto interval_us = static_cast<int32_t>(command.params.param2);
×
UNCOV
2092
    UNUSED(message_id);
×
2093

2094
    // Interval value of -1 means to disable sending messages
2095
    if (interval_us < 0) {
×
UNCOV
2096
        stop_sending_tracking_status();
×
2097
    } else {
2098
        start_sending_tracking_status(interval_us);
×
2099
    }
2100

2101
    // Always send the "Accepted" result
UNCOV
2102
    return _server_component_impl->make_command_ack_message(
×
2103
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
2104
}
2105

2106
void CameraServerImpl::send_tracking_status_with_interval(uint32_t interval_us)
×
2107
{
2108
    while (true) {
UNCOV
2109
        std::this_thread::sleep_for(std::chrono::microseconds{interval_us});
×
2110
        {
2111
            std::scoped_lock lg{_mutex};
×
2112
            if (!_sending_tracking_status) {
×
UNCOV
2113
                return;
×
2114
            }
2115
        }
×
2116
        _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
2117
            mavlink_message_t message;
2118
            std::lock_guard<std::mutex> lg{_mutex};
×
2119

2120
            // The message is filled based on current tracking mode
UNCOV
2121
            switch (_tracking_mode) {
×
2122
                default:
×
2123
                    // Fallthrough
2124
                case TrackingMode::NONE:
2125

2126
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
UNCOV
2127
                        mavlink_address.system_id,
×
UNCOV
2128
                        mavlink_address.component_id,
×
2129
                        channel,
2130
                        &message,
2131
                        CAMERA_TRACKING_STATUS_FLAGS_IDLE,
2132
                        CAMERA_TRACKING_MODE_NONE,
2133
                        CAMERA_TRACKING_TARGET_DATA_NONE,
2134
                        0.0f,
2135
                        0.0f,
2136
                        0.0f,
2137
                        0.0f,
2138
                        0.0f,
2139
                        0.0f,
2140
                        0.0f,
2141
                        0);
2142
                    break;
×
UNCOV
2143
                case TrackingMode::POINT:
×
2144

UNCOV
2145
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
2146
                        mavlink_address.system_id,
×
2147
                        mavlink_address.component_id,
×
2148
                        channel,
2149
                        &message,
2150
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
2151
                        CAMERA_TRACKING_MODE_POINT,
2152
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
2153
                        _tracked_point.point_x,
2154
                        _tracked_point.point_y,
2155
                        _tracked_point.radius,
2156
                        0.0f,
2157
                        0.0f,
2158
                        0.0f,
2159
                        0.0f,
2160
                        0);
UNCOV
2161
                    break;
×
2162

2163
                case TrackingMode::RECTANGLE:
×
2164

2165
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
2166
                        mavlink_address.system_id,
×
2167
                        mavlink_address.component_id,
×
2168
                        channel,
2169
                        &message,
2170
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
2171
                        CAMERA_TRACKING_MODE_RECTANGLE,
2172
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
2173
                        0.0f,
2174
                        0.0f,
2175
                        0.0f,
2176
                        _tracked_rectangle.top_left_corner_x,
2177
                        _tracked_rectangle.top_left_corner_y,
2178
                        _tracked_rectangle.bottom_right_corner_x,
2179
                        _tracked_rectangle.bottom_right_corner_y,
2180
                        0);
2181
                    break;
×
2182
            }
2183
            return message;
×
UNCOV
2184
        });
×
2185
    }
×
2186
}
2187

UNCOV
2188
void CameraServerImpl::start_sending_tracking_status(uint32_t interval_ms)
×
2189
{
2190
    // Stop sending status with the old interval
UNCOV
2191
    stop_sending_tracking_status();
×
2192

UNCOV
2193
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
2194
    _sending_tracking_status = true;
×
UNCOV
2195
    _tracking_status_sending_thread =
×
UNCOV
2196
        std::thread{&CameraServerImpl::send_tracking_status_with_interval, this, interval_ms};
×
UNCOV
2197
}
×
2198

UNCOV
2199
void CameraServerImpl::stop_sending_tracking_status()
×
2200
{
2201
    // Firstly, ask the other thread to stop sending the status
2202
    {
2203
        std::scoped_lock lg{_mutex};
×
2204
        _sending_tracking_status = false;
×
2205
    }
×
2206
    // If the thread was active, wait for it to finish
UNCOV
2207
    if (_tracking_status_sending_thread.joinable()) {
×
2208
        _tracking_status_sending_thread.join();
×
2209
    }
UNCOV
2210
}
×
2211

UNCOV
2212
void CameraServerImpl::start_sending_capture_status()
×
2213
{
2214
    _capture_status_timer_cookie = _server_component_impl->add_call_every(
×
2215
        [this]() { send_capture_status(); }, CAPTURE_STATUS_INTERVAL_S);
×
2216
}
×
2217

2218
void CameraServerImpl::stop_sending_capture_status()
9✔
2219
{
2220
    _server_component_impl->remove_call_every(_capture_status_timer_cookie);
9✔
2221
}
9✔
2222

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