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

mavlink / MAVSDK / 16461760413

23 Jul 2025 04:44AM UTC coverage: 45.203% (+0.1%) from 45.093%
16461760413

Pull #2621

github

web-flow
Merge 23594c6eb into ae05b10ff
Pull Request #2621: CameraServer improvements

46 of 125 new or added lines in 1 file covered. (36.8%)

291 existing lines in 2 files now uncovered.

15435 of 34146 relevant lines covered (45.2%)

290.27 hits per line

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

37.05
/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
    bool should_send_capture_status = false;
×
432

433
    {
NEW
434
        std::lock_guard<std::mutex> lg{_mutex};
×
435

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

NEW
463
    if (should_send_capture_status) {
×
NEW
464
        send_capture_status();
×
465
    }
466

467
    return CameraServer::Result::Success;
×
468
}
469

470
CameraServer::StopVideoHandle
UNCOV
471
CameraServerImpl::subscribe_stop_video(const CameraServer::StopVideoCallback& callback)
×
472
{
473
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
474
    return _stop_video_callbacks.subscribe(callback);
×
475
}
×
476

477
void CameraServerImpl::unsubscribe_stop_video(CameraServer::StopVideoHandle handle)
×
478
{
479
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
480
    return _stop_video_callbacks.unsubscribe(handle);
×
481
}
×
482

483
CameraServer::Result
UNCOV
484
CameraServerImpl::respond_stop_video(CameraServer::CameraFeedback stop_video_feedback)
×
485
{
486
    bool should_send_capture_status = false;
×
487

488
    {
UNCOV
489
        std::lock_guard<std::mutex> lg{_mutex};
×
490

NEW
491
        switch (stop_video_feedback) {
×
NEW
492
            default:
×
493
                // Fallthrough
494
            case CameraServer::CameraFeedback::Unknown:
NEW
495
                return CameraServer::Result::Error;
×
NEW
496
            case CameraServer::CameraFeedback::Ok: {
×
NEW
497
                auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
498
                    _last_stop_video_command, MAV_RESULT_ACCEPTED);
×
NEW
499
                _server_component_impl->send_command_ack(command_ack);
×
NEW
500
                should_send_capture_status = true;
×
NEW
501
                break;
×
502
            }
NEW
503
            case CameraServer::CameraFeedback::Busy: {
×
NEW
504
                auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
505
                    _last_stop_video_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
NEW
506
                _server_component_impl->send_command_ack(command_ack);
×
NEW
507
                return CameraServer::Result::Success;
×
508
            }
NEW
509
            case CameraServer::CameraFeedback::Failed: {
×
NEW
510
                auto command_ack = _server_component_impl->make_command_ack_message(
×
NEW
511
                    _last_stop_video_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
NEW
512
                _server_component_impl->send_command_ack(command_ack);
×
NEW
513
                return CameraServer::Result::Success;
×
514
            }
515
        }
NEW
516
    } // Release mutex
×
517

UNCOV
518
    if (should_send_capture_status) {
×
NEW
519
        send_capture_status();
×
520
    }
521

NEW
522
    return CameraServer::Result::Success;
×
523
}
524

NEW
525
CameraServer::StartVideoStreamingHandle CameraServerImpl::subscribe_start_video_streaming(
×
526
    const CameraServer::StartVideoStreamingCallback& callback)
527
{
528
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
529
    return _start_video_streaming_callbacks.subscribe(callback);
×
UNCOV
530
}
×
531

532
void CameraServerImpl::unsubscribe_start_video_streaming(
×
533
    CameraServer::StartVideoStreamingHandle handle)
534
{
535
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
536
    return _start_video_streaming_callbacks.unsubscribe(handle);
×
UNCOV
537
}
×
538

539
CameraServer::Result CameraServerImpl::respond_start_video_streaming(
×
540
    CameraServer::CameraFeedback start_video_streaming_feedback)
541
{
542
    std::lock_guard<std::mutex> lg{_mutex};
×
543

UNCOV
544
    switch (start_video_streaming_feedback) {
×
545
        default:
×
546
            // Fallthrough
547
        case CameraServer::CameraFeedback::Unknown:
548
            return CameraServer::Result::Error;
×
UNCOV
549
        case CameraServer::CameraFeedback::Ok: {
×
UNCOV
550
            auto command_ack = _server_component_impl->make_command_ack_message(
×
551
                _last_start_video_streaming_command, MAV_RESULT_ACCEPTED);
×
552
            _server_component_impl->send_command_ack(command_ack);
×
553
            return CameraServer::Result::Success;
×
554
        }
555
        case CameraServer::CameraFeedback::Busy: {
×
556
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
557
                _last_start_video_streaming_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
558
            _server_component_impl->send_command_ack(command_ack);
×
559
            return CameraServer::Result::Success;
×
560
        }
561
        case CameraServer::CameraFeedback::Failed: {
×
562
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
563
                _last_start_video_streaming_command, MAV_RESULT_FAILED);
×
564
            _server_component_impl->send_command_ack(command_ack);
×
565
            return CameraServer::Result::Success;
×
566
        }
567
    }
568
}
×
569

UNCOV
570
CameraServer::StopVideoStreamingHandle CameraServerImpl::subscribe_stop_video_streaming(
×
571
    const CameraServer::StopVideoStreamingCallback& callback)
572
{
573
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
574
    return _stop_video_streaming_callbacks.subscribe(callback);
×
UNCOV
575
}
×
576

577
void CameraServerImpl::unsubscribe_stop_video_streaming(
×
578
    CameraServer::StopVideoStreamingHandle handle)
579
{
580
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
581
    return _stop_video_streaming_callbacks.unsubscribe(handle);
×
UNCOV
582
}
×
583

584
CameraServer::Result CameraServerImpl::respond_stop_video_streaming(
×
585
    CameraServer::CameraFeedback stop_video_streaming_feedback)
586
{
587
    std::lock_guard<std::mutex> lg{_mutex};
×
588

UNCOV
589
    switch (stop_video_streaming_feedback) {
×
590
        default:
×
591
            // Fallthrough
592
        case CameraServer::CameraFeedback::Unknown:
593
            return CameraServer::Result::Error;
×
UNCOV
594
        case CameraServer::CameraFeedback::Ok: {
×
UNCOV
595
            auto command_ack = _server_component_impl->make_command_ack_message(
×
596
                _last_stop_video_streaming_command, MAV_RESULT_ACCEPTED);
×
597
            _server_component_impl->send_command_ack(command_ack);
×
598
            return CameraServer::Result::Success;
×
599
        }
600
        case CameraServer::CameraFeedback::Busy: {
×
601
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
602
                _last_stop_video_streaming_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
603
            _server_component_impl->send_command_ack(command_ack);
×
604
            return CameraServer::Result::Success;
×
605
        }
606
        case CameraServer::CameraFeedback::Failed: {
×
607
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
608
                _last_stop_video_streaming_command, MAV_RESULT_FAILED);
×
609
            _server_component_impl->send_command_ack(command_ack);
×
610
            return CameraServer::Result::Success;
×
611
        }
612
    }
613
}
×
614

615
CameraServer::SetModeHandle
616
CameraServerImpl::subscribe_set_mode(const CameraServer::SetModeCallback& callback)
2✔
617
{
618
    std::lock_guard<std::mutex> lg{_mutex};
2✔
619
    return _set_mode_callbacks.subscribe(callback);
2✔
620
}
2✔
621

622
void CameraServerImpl::unsubscribe_set_mode(CameraServer::SetModeHandle handle)
1✔
623
{
624
    std::lock_guard<std::mutex> lg{_mutex};
1✔
625
    _set_mode_callbacks.unsubscribe(handle);
1✔
626
}
1✔
627

628
CameraServer::Result
629
CameraServerImpl::respond_set_mode(CameraServer::CameraFeedback set_mode_feedback)
2✔
630
{
631
    std::lock_guard<std::mutex> lg{_mutex};
2✔
632

633
    switch (set_mode_feedback) {
2✔
UNCOV
634
        default:
×
635
            // Fallthrough
636
        case CameraServer::CameraFeedback::Unknown:
637
            return CameraServer::Result::Error;
×
638
        case CameraServer::CameraFeedback::Ok: {
2✔
639
            auto command_ack = _server_component_impl->make_command_ack_message(
2✔
640
                _last_set_mode_command, MAV_RESULT_ACCEPTED);
2✔
641
            _server_component_impl->send_command_ack(command_ack);
2✔
642
            return CameraServer::Result::Success;
2✔
643
        }
UNCOV
644
        case CameraServer::CameraFeedback::Busy: {
×
UNCOV
645
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
646
                _last_set_mode_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
647
            _server_component_impl->send_command_ack(command_ack);
×
648
            return CameraServer::Result::Success;
×
649
        }
650
        case CameraServer::CameraFeedback::Failed: {
×
651
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
652
                _last_set_mode_command, MAV_RESULT_FAILED);
×
653
            _server_component_impl->send_command_ack(command_ack);
×
654
            return CameraServer::Result::Success;
×
655
        }
656
    }
657
}
2✔
658

659
CameraServer::StorageInformationHandle CameraServerImpl::subscribe_storage_information(
1✔
660
    const CameraServer::StorageInformationCallback& callback)
661
{
662
    std::lock_guard<std::mutex> lg{_mutex};
1✔
663
    return _storage_information_callbacks.subscribe(callback);
1✔
664
}
1✔
665

UNCOV
666
void CameraServerImpl::unsubscribe_storage_information(
×
667
    CameraServer::StorageInformationHandle handle)
668
{
669
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
670
    _storage_information_callbacks.unsubscribe(handle);
×
UNCOV
671
}
×
672

673
CameraServer::Result CameraServerImpl::respond_storage_information(
2✔
674
    CameraServer::CameraFeedback storage_information_feedback,
675
    CameraServer::StorageInformation storage_information)
676
{
677
    std::lock_guard<std::mutex> lg{_mutex};
2✔
678

679
    switch (storage_information_feedback) {
2✔
UNCOV
680
        default:
×
681
            // Fallthrough
682
        case CameraServer::CameraFeedback::Unknown:
683
            return CameraServer::Result::Error;
×
684
        case CameraServer::CameraFeedback::Ok: {
2✔
685
            auto command_ack = _server_component_impl->make_command_ack_message(
2✔
686
                _last_storage_information_command, MAV_RESULT_ACCEPTED);
2✔
687
            _server_component_impl->send_command_ack(command_ack);
2✔
688
            // break and send storage information
689
            break;
2✔
690
        }
UNCOV
691
        case CameraServer::CameraFeedback::Busy: {
×
UNCOV
692
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
693
                _last_storage_information_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
694
            _server_component_impl->send_command_ack(command_ack);
×
695
            return CameraServer::Result::Success;
×
696
        }
697
        case CameraServer::CameraFeedback::Failed: {
×
698
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
699
                _last_storage_information_command, MAV_RESULT_FAILED);
×
700
            _server_component_impl->send_command_ack(command_ack);
×
701
            return CameraServer::Result::Success;
×
702
        }
703
    }
704

705
    const uint8_t storage_count = 1;
2✔
706

707
    const float total_capacity = storage_information.total_storage_mib;
2✔
708
    const float used_capacity = storage_information.used_storage_mib;
2✔
709
    const float available_capacity = storage_information.available_storage_mib;
2✔
710
    const float read_speed = storage_information.read_speed_mib_s;
2✔
711
    const float write_speed = storage_information.write_speed_mib_s;
2✔
712

713
    auto status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
2✔
714
    switch (storage_information.storage_status) {
2✔
UNCOV
715
        case CameraServer::StorageInformation::StorageStatus::NotAvailable:
×
UNCOV
716
            status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
UNCOV
717
            break;
×
718
        case CameraServer::StorageInformation::StorageStatus::Unformatted:
×
719
            status = STORAGE_STATUS::STORAGE_STATUS_UNFORMATTED;
×
720
            break;
×
721
        case CameraServer::StorageInformation::StorageStatus::Formatted:
2✔
722
            status = STORAGE_STATUS::STORAGE_STATUS_READY;
2✔
723
            break;
2✔
UNCOV
724
        case CameraServer::StorageInformation::StorageStatus::NotSupported:
×
UNCOV
725
            status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
UNCOV
726
            break;
×
727
    }
728

729
    auto type = STORAGE_TYPE::STORAGE_TYPE_UNKNOWN;
2✔
730
    switch (storage_information.storage_type) {
2✔
UNCOV
731
        case CameraServer::StorageInformation::StorageType::UsbStick:
×
UNCOV
732
            type = STORAGE_TYPE::STORAGE_TYPE_USB_STICK;
×
UNCOV
733
            break;
×
734
        case CameraServer::StorageInformation::StorageType::Sd:
×
735
            type = STORAGE_TYPE::STORAGE_TYPE_SD;
×
736
            break;
×
737
        case CameraServer::StorageInformation::StorageType::Microsd:
×
738
            type = STORAGE_TYPE::STORAGE_TYPE_MICROSD;
×
739
            break;
×
740
        case CameraServer::StorageInformation::StorageType::Hd:
×
741
            type = STORAGE_TYPE::STORAGE_TYPE_HD;
×
742
            break;
×
743
        case CameraServer::StorageInformation::StorageType::Other:
×
744
            type = STORAGE_TYPE::STORAGE_TYPE_OTHER;
×
745
            break;
×
746
        default:
2✔
747
            break;
2✔
748
    }
749

750
    std::string name("");
4✔
751
    // This needs to be long enough, otherwise the memcpy in mavlink overflows.
752
    name.resize(32);
2✔
753
    const uint8_t storage_usage = 0;
2✔
754

755
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
2✔
756
        mavlink_message_t message{};
2✔
757
        mavlink_msg_storage_information_pack_chan(
4✔
758
            mavlink_address.system_id,
2✔
759
            mavlink_address.component_id,
2✔
760
            channel,
761
            &message,
762
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
2✔
763
            _last_storage_id,
2✔
764
            storage_count,
765
            status,
2✔
766
            total_capacity,
2✔
767
            used_capacity,
2✔
768
            available_capacity,
2✔
769
            read_speed,
2✔
770
            write_speed,
2✔
771
            type,
2✔
772
            name.data(),
2✔
773
            storage_usage);
774
        return message;
2✔
775
    });
776

777
    return CameraServer::Result::Success;
2✔
778
}
2✔
779

780
CameraServer::CaptureStatusHandle
UNCOV
781
CameraServerImpl::subscribe_capture_status(const CameraServer::CaptureStatusCallback& callback)
×
782
{
UNCOV
783
    CameraServer::CaptureStatusHandle handle;
×
784
    bool should_start_timer = false;
×
785

786
    {
NEW
787
        std::lock_guard<std::mutex> lg{_mutex};
×
NEW
788
        should_start_timer = _capture_status_callbacks.empty();
×
NEW
789
        handle = _capture_status_callbacks.subscribe(callback);
×
NEW
790
    }
×
791

NEW
792
    if (should_start_timer) {
×
NEW
793
        start_sending_capture_status();
×
794
    }
795

NEW
796
    return handle;
×
797
}
798

NEW
799
void CameraServerImpl::unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle)
×
800
{
UNCOV
801
    bool should_stop_timer = false;
×
802

803
    {
NEW
804
        std::lock_guard<std::mutex> lg{_mutex};
×
NEW
805
        _capture_status_callbacks.unsubscribe(handle);
×
NEW
806
        should_stop_timer = _capture_status_callbacks.empty();
×
NEW
807
    }
×
808

NEW
809
    if (should_stop_timer) {
×
NEW
810
        stop_sending_capture_status();
×
811
    }
NEW
812
}
×
813

NEW
814
CameraServer::Result CameraServerImpl::respond_capture_status(
×
815
    CameraServer::CameraFeedback capture_status_feedback,
816
    CameraServer::CaptureStatus capture_status)
817
{
818
    {
UNCOV
819
        std::lock_guard<std::mutex> lg{_mutex};
×
820

UNCOV
821
        switch (capture_status_feedback) {
×
822
            default:
×
823
                // Fallthrough
824
            case CameraServer::CameraFeedback::Unknown:
825
                return CameraServer::Result::Error;
×
UNCOV
826
            case CameraServer::CameraFeedback::Ok: {
×
UNCOV
827
                auto command_ack = _server_component_impl->make_command_ack_message(
×
828
                    _last_capture_status_command, MAV_RESULT_ACCEPTED);
×
829
                _server_component_impl->send_command_ack(command_ack);
×
830
                // break and send capture status
831
                break;
×
832
            }
UNCOV
833
            case CameraServer::CameraFeedback::Busy: {
×
834
                auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
835
                    _last_capture_status_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
836
                _server_component_impl->send_command_ack(command_ack);
×
837
                return CameraServer::Result::Success;
×
838
            }
839
            case CameraServer::CameraFeedback::Failed: {
×
840
                auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
841
                    _last_capture_status_command, MAV_RESULT_FAILED);
×
842
                _server_component_impl->send_command_ack(command_ack);
×
843
                return CameraServer::Result::Success;
×
844
            }
845
        }
846

UNCOV
847
        _capture_status = capture_status;
×
UNCOV
848
    }
×
849

850
    send_capture_status();
×
851

UNCOV
852
    return CameraServer::Result::Success;
×
853
}
854

855
CameraServer::FormatStorageHandle
856
CameraServerImpl::subscribe_format_storage(const CameraServer::FormatStorageCallback& callback)
1✔
857
{
858
    std::lock_guard<std::mutex> lg{_mutex};
1✔
859
    return _format_storage_callbacks.subscribe(callback);
1✔
860
}
1✔
861
void CameraServerImpl::unsubscribe_format_storage(CameraServer::FormatStorageHandle handle)
1✔
862
{
863
    std::lock_guard<std::mutex> lg{_mutex};
1✔
864
    _format_storage_callbacks.unsubscribe(handle);
1✔
865
}
1✔
866

867
CameraServer::Result
868
CameraServerImpl::respond_format_storage(CameraServer::CameraFeedback format_storage_feedback)
1✔
869
{
870
    std::lock_guard<std::mutex> lg{_mutex};
1✔
871

872
    switch (format_storage_feedback) {
1✔
UNCOV
873
        default:
×
874
            // Fallthrough
875
        case CameraServer::CameraFeedback::Unknown:
876
            return CameraServer::Result::Error;
×
877
        case CameraServer::CameraFeedback::Ok: {
1✔
878
            auto command_ack = _server_component_impl->make_command_ack_message(
1✔
879
                _last_format_storage_command, MAV_RESULT_ACCEPTED);
1✔
880
            _server_component_impl->send_command_ack(command_ack);
1✔
881
            return CameraServer::Result::Success;
1✔
882
        }
UNCOV
883
        case CameraServer::CameraFeedback::Busy: {
×
UNCOV
884
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
885
                _last_format_storage_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
886
            _server_component_impl->send_command_ack(command_ack);
×
887
            return CameraServer::Result::Success;
×
888
        }
889
        case CameraServer::CameraFeedback::Failed: {
×
890
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
891
                _last_format_storage_command, MAV_RESULT_FAILED);
×
892
            _server_component_impl->send_command_ack(command_ack);
×
893
            return CameraServer::Result::Success;
×
894
        }
895
    }
896
}
1✔
897

898
CameraServer::ResetSettingsHandle
899
CameraServerImpl::subscribe_reset_settings(const CameraServer::ResetSettingsCallback& callback)
1✔
900
{
901
    std::lock_guard<std::mutex> lg{_mutex};
1✔
902
    return _reset_settings_callbacks.subscribe(callback);
1✔
903
}
1✔
904

UNCOV
905
void CameraServerImpl::unsubscribe_reset_settings(CameraServer::ResetSettingsHandle handle)
×
906
{
UNCOV
907
    std::lock_guard<std::mutex> lg{_mutex};
×
908
    _reset_settings_callbacks.unsubscribe(handle);
×
UNCOV
909
}
×
910

911
CameraServer::Result
912
CameraServerImpl::respond_reset_settings(CameraServer::CameraFeedback reset_settings_feedback)
1✔
913
{
914
    std::lock_guard<std::mutex> lg{_mutex};
1✔
915

916
    switch (reset_settings_feedback) {
1✔
UNCOV
917
        default:
×
918
            // Fallthrough
919
        case CameraServer::CameraFeedback::Unknown:
920
            return CameraServer::Result::Error;
×
921
        case CameraServer::CameraFeedback::Ok: {
1✔
922
            auto command_ack = _server_component_impl->make_command_ack_message(
1✔
923
                _last_reset_settings_command, MAV_RESULT_ACCEPTED);
1✔
924
            _server_component_impl->send_command_ack(command_ack);
1✔
925
            return CameraServer::Result::Success;
1✔
926
        }
UNCOV
927
        case CameraServer::CameraFeedback::Busy: {
×
UNCOV
928
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
929
                _last_reset_settings_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
930
            _server_component_impl->send_command_ack(command_ack);
×
931
            return CameraServer::Result::Success;
×
932
        }
933
        case CameraServer::CameraFeedback::Failed: {
×
934
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
935
                _last_reset_settings_command, MAV_RESULT_FAILED);
×
936
            _server_component_impl->send_command_ack(command_ack);
×
937
            return CameraServer::Result::Success;
×
938
        }
939
    }
940
}
1✔
941

UNCOV
942
CameraServer::TrackingPointCommandHandle CameraServerImpl::subscribe_tracking_point_command(
×
943
    const CameraServer::TrackingPointCommandCallback& callback)
944
{
945
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
946
    return _tracking_point_callbacks.subscribe(callback);
×
UNCOV
947
}
×
948

949
void CameraServerImpl::unsubscribe_tracking_point_command(
×
950
    CameraServer::TrackingPointCommandHandle handle)
951
{
952
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
953
    _tracking_point_callbacks.unsubscribe(handle);
×
UNCOV
954
}
×
955

956
CameraServer::Result CameraServerImpl::respond_tracking_point_command(
×
957
    CameraServer::CameraFeedback tracking_point_feedback)
958
{
959
    std::lock_guard<std::mutex> lg{_mutex};
×
960

UNCOV
961
    switch (tracking_point_feedback) {
×
962
        default:
×
963
            // Fallthrough
964
        case CameraServer::CameraFeedback::Unknown:
965
            return CameraServer::Result::Error;
×
UNCOV
966
        case CameraServer::CameraFeedback::Ok: {
×
UNCOV
967
            auto command_ack = _server_component_impl->make_command_ack_message(
×
968
                _last_track_point_command, MAV_RESULT_ACCEPTED);
×
969
            _server_component_impl->send_command_ack(command_ack);
×
970
            break;
×
971
        }
972
        case CameraServer::CameraFeedback::Busy: {
×
973
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
974
                _last_track_point_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
975
            _server_component_impl->send_command_ack(command_ack);
×
976
            return CameraServer::Result::Success;
×
977
        }
978
        case CameraServer::CameraFeedback::Failed: {
×
979
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
980
                _last_track_point_command, MAV_RESULT_FAILED);
×
981
            _server_component_impl->send_command_ack(command_ack);
×
982
            return CameraServer::Result::Success;
×
983
        }
984
    }
985
    return CameraServer::Result::Success;
×
UNCOV
986
}
×
987

988
CameraServer::TrackingRectangleCommandHandle CameraServerImpl::subscribe_tracking_rectangle_command(
×
989
    const CameraServer::TrackingRectangleCommandCallback& callback)
990
{
991
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
992
    return _tracking_rectangle_callbacks.subscribe(callback);
×
UNCOV
993
}
×
994

995
void CameraServerImpl::unsubscribe_tracking_rectangle_command(
×
996
    CameraServer::TrackingRectangleCommandHandle handle)
997
{
998
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
999
    _tracking_rectangle_callbacks.unsubscribe(handle);
×
UNCOV
1000
}
×
1001

1002
CameraServer::Result CameraServerImpl::respond_tracking_rectangle_command(
×
1003
    CameraServer::CameraFeedback tracking_rectangle_feedback)
1004
{
1005
    std::lock_guard<std::mutex> lg{_mutex};
×
1006

UNCOV
1007
    switch (tracking_rectangle_feedback) {
×
1008
        default:
×
1009
            // Fallthrough
1010
        case CameraServer::CameraFeedback::Unknown:
1011
            return CameraServer::Result::Error;
×
UNCOV
1012
        case CameraServer::CameraFeedback::Ok: {
×
UNCOV
1013
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1014
                _last_track_rectangle_command, MAV_RESULT_ACCEPTED);
×
1015
            _server_component_impl->send_command_ack(command_ack);
×
1016
            break;
×
1017
        }
1018
        case CameraServer::CameraFeedback::Busy: {
×
1019
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1020
                _last_track_rectangle_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1021
            _server_component_impl->send_command_ack(command_ack);
×
1022
            return CameraServer::Result::Success;
×
1023
        }
1024
        case CameraServer::CameraFeedback::Failed: {
×
1025
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1026
                _last_track_rectangle_command, MAV_RESULT_FAILED);
×
1027
            _server_component_impl->send_command_ack(command_ack);
×
1028
            return CameraServer::Result::Success;
×
1029
        }
1030
    }
1031
    return CameraServer::Result::Success;
×
UNCOV
1032
}
×
1033

1034
CameraServer::TrackingOffCommandHandle CameraServerImpl::subscribe_tracking_off_command(
×
1035
    const CameraServer::TrackingOffCommandCallback& callback)
1036
{
1037
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1038
    return _tracking_off_callbacks.subscribe(callback);
×
UNCOV
1039
}
×
1040

1041
void CameraServerImpl::unsubscribe_tracking_off_command(
×
1042
    CameraServer::TrackingOffCommandHandle handle)
1043
{
1044
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1045
    _tracking_off_callbacks.unsubscribe(handle);
×
UNCOV
1046
}
×
1047

1048
CameraServer::Result
1049
CameraServerImpl::respond_tracking_off_command(CameraServer::CameraFeedback tracking_off_feedback)
×
1050
{
UNCOV
1051
    std::lock_guard<std::mutex> lg{_mutex};
×
1052

UNCOV
1053
    switch (tracking_off_feedback) {
×
1054
        default:
×
1055
            // Fallthrough
1056
        case CameraServer::CameraFeedback::Unknown:
1057
            return CameraServer::Result::Error;
×
UNCOV
1058
        case CameraServer::CameraFeedback::Ok: {
×
UNCOV
1059
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1060
                _last_tracking_off_command, MAV_RESULT_ACCEPTED);
×
1061
            _server_component_impl->send_command_ack(command_ack);
×
1062
            break;
×
1063
        }
1064
        case CameraServer::CameraFeedback::Busy: {
×
1065
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1066
                _last_tracking_off_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1067
            _server_component_impl->send_command_ack(command_ack);
×
1068
            return CameraServer::Result::Success;
×
1069
        }
1070
        case CameraServer::CameraFeedback::Failed: {
×
1071
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1072
                _last_tracking_off_command, MAV_RESULT_FAILED);
×
1073
            _server_component_impl->send_command_ack(command_ack);
×
1074
            return CameraServer::Result::Success;
×
1075
        }
1076
    }
1077
    return CameraServer::Result::Success;
×
UNCOV
1078
}
×
1079

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

1085
    _last_interval_index = index;
1✔
1086

1087
    _image_capture_timer_cookie = _server_component_impl->add_call_every(
1✔
1088
        [this, remaining]() {
15✔
1089
            LogDebug() << "capture image timer triggered";
3✔
1090

1091
            if (!_take_photo_callbacks.empty()) {
3✔
1092
                _take_photo_callbacks.queue(_last_interval_index++, [this](const auto& func) {
3✔
1093
                    _server_component_impl->call_user_callback(func);
3✔
1094
                });
3✔
1095
                (*remaining)--;
3✔
1096
            }
1097

1098
            if (*remaining == 0) {
3✔
UNCOV
1099
                stop_image_capture_interval();
×
1100
            }
1101
        },
3✔
1102
        interval_s);
1103

1104
    _is_image_capture_interval_set = true;
1✔
1105
    _image_capture_timer_interval_s = interval_s;
1✔
1106
}
1✔
1107

1108
void CameraServerImpl::stop_image_capture_interval()
12✔
1109
{
1110
    _server_component_impl->remove_call_every(_image_capture_timer_cookie);
12✔
1111

1112
    std::lock_guard<std::mutex> lg{_mutex};
12✔
1113
    _is_image_capture_interval_set = false;
12✔
1114
    _image_capture_timer_interval_s = 0;
12✔
1115
}
12✔
1116

UNCOV
1117
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_information_request(
×
1118
    const MavlinkCommandReceiver::CommandLong& command)
1119
{
1120
    LogDebug() << "Camera info request";
×
1121

UNCOV
1122
    if (static_cast<int>(command.params.param1) == 0) {
×
1123
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1124
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1125
    }
1126

1127
    return send_camera_information(command);
×
1128
}
1129

1130
std::optional<mavlink_command_ack_t>
1131
CameraServerImpl::process_request_message(const MavlinkCommandReceiver::CommandLong& command)
97✔
1132
{
1133
    switch (static_cast<int>(command.params.param1)) {
97✔
1134
        case MAVLINK_MSG_ID_CAMERA_INFORMATION:
9✔
1135
            return send_camera_information(command);
9✔
1136

1137
        case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS:
9✔
1138
            send_capture_status();
9✔
1139
            return _server_component_impl->make_command_ack_message(
18✔
1140
                command, MAV_RESULT::MAV_RESULT_ACCEPTED);
18✔
1141

1142
        default:
79✔
1143
            LogWarn() << "Got unknown request message!";
79✔
1144
            return _server_component_impl->make_command_ack_message(
158✔
1145
                command, MAV_RESULT::MAV_RESULT_DENIED);
158✔
1146
    }
1147
}
1148

1149
std::optional<mavlink_command_ack_t>
1150
CameraServerImpl::send_camera_information(const MavlinkCommandReceiver::CommandLong& command)
9✔
1151
{
1152
    std::lock_guard<std::mutex> lg{_mutex};
9✔
1153

1154
    if (!_is_information_set) {
9✔
UNCOV
1155
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1156
            command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED);
×
1157
    }
1158

1159
    // ack needs to be sent before camera information message
1160
    auto command_ack =
9✔
1161
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
9✔
1162
    _server_component_impl->send_command_ack(command_ack);
9✔
1163

1164
    // It is safe to ignore the return value of parse_version_string() here
1165
    // since the string was already validated in set_information().
1166
    uint32_t firmware_version;
9✔
1167
    parse_version_string(_information.firmware_version, firmware_version);
9✔
1168

1169
    // capability flags are determined by subscriptions
1170
    uint32_t capability_flags{};
9✔
1171

1172
    if (!_take_photo_callbacks.empty()) {
9✔
1173
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE;
2✔
1174
    }
1175

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

1180
    if (!_set_mode_callbacks.empty()) {
9✔
1181
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES;
2✔
1182
    }
1183

1184
    if (_information.image_in_video_mode_supported) {
9✔
UNCOV
1185
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE;
×
1186
    }
1187

1188
    if (_information.video_in_image_mode_supported) {
9✔
UNCOV
1189
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE;
×
1190
    }
1191

1192
    if (_is_video_streaming_set) {
9✔
1193
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM;
1✔
1194
    }
1195

1196
    if (!_tracking_point_callbacks.empty()) {
9✔
UNCOV
1197
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT;
×
1198
    }
1199

1200
    if (!_tracking_rectangle_callbacks.empty()) {
9✔
UNCOV
1201
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE;
×
1202
    }
1203

1204
    if (!_zoom_range_callbacks.empty() || !_zoom_in_start_callbacks.empty() ||
18✔
1205
        !_zoom_out_start_callbacks.empty()) {
9✔
UNCOV
1206
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM;
×
1207
    }
1208

1209
    _information.vendor_name.resize(sizeof(mavlink_camera_information_t::vendor_name));
9✔
1210
    _information.model_name.resize(sizeof(mavlink_camera_information_t::model_name));
9✔
1211
    _information.definition_file_uri.resize(
9✔
1212
        sizeof(mavlink_camera_information_t::cam_definition_uri));
1213

1214
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
9✔
1215
        mavlink_message_t message{};
9✔
1216
        mavlink_msg_camera_information_pack_chan(
27✔
1217
            mavlink_address.system_id,
9✔
1218
            mavlink_address.component_id,
9✔
1219
            channel,
1220
            &message,
1221
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
18✔
1222
            reinterpret_cast<const uint8_t*>(_information.vendor_name.c_str()),
9✔
1223
            reinterpret_cast<const uint8_t*>(_information.model_name.c_str()),
9✔
1224
            firmware_version,
9✔
1225
            _information.focal_length_mm,
1226
            _information.horizontal_sensor_size_mm,
1227
            _information.vertical_sensor_size_mm,
1228
            _information.horizontal_resolution_px,
9✔
1229
            _information.vertical_resolution_px,
9✔
1230
            _information.lens_id,
9✔
1231
            capability_flags,
9✔
1232
            _information.definition_file_version,
9✔
1233
            _information.definition_file_uri.c_str(),
1234
            0,
1235
            0);
1236
        return message;
9✔
1237
    });
1238

1239
    return std::nullopt;
9✔
1240
}
9✔
1241

1242
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_settings_request(
9✔
1243
    const MavlinkCommandReceiver::CommandLong& command)
1244
{
1245
    auto settings = static_cast<bool>(command.params.param1);
9✔
1246

1247
    if (!settings) {
9✔
UNCOV
1248
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1249
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1250
    }
1251

1252
    // ack needs to be sent before camera information message
1253
    auto command_ack =
9✔
1254
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
9✔
1255
    _server_component_impl->send_command_ack(command_ack);
9✔
1256
    LogDebug() << "sent settings ack";
9✔
1257

1258
    // unsupported
1259
    const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE;
9✔
1260
    const float zoom_level = 0;
9✔
1261
    const float focus_level = 0;
9✔
1262

1263
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
9✔
1264
        mavlink_message_t message{};
9✔
1265
        mavlink_msg_camera_settings_pack_chan(
18✔
1266
            mavlink_address.system_id,
9✔
1267
            mavlink_address.component_id,
9✔
1268
            channel,
1269
            &message,
1270
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
9✔
1271
            mode_id,
1272
            zoom_level,
9✔
1273
            focus_level,
9✔
1274
            0);
1275
        return message;
9✔
1276
    });
1277
    LogDebug() << "sent settings msg";
9✔
1278

1279
    // ack was already sent
1280
    return std::nullopt;
9✔
1281
}
1282

1283
std::optional<mavlink_command_ack_t> CameraServerImpl::process_storage_information_request(
16✔
1284
    const MavlinkCommandReceiver::CommandLong& command)
1285
{
1286
    auto storage_id = static_cast<uint8_t>(command.params.param1);
16✔
1287
    auto information = static_cast<bool>(command.params.param2);
16✔
1288

1289
    if (!information) {
16✔
UNCOV
1290
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1291
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1292
    }
1293

1294
    std::lock_guard<std::mutex> lg{_mutex};
16✔
1295

1296
    if (_storage_information_callbacks.empty()) {
16✔
1297
        LogDebug()
28✔
1298
            << "Get storage information requested with no set storage information subscriber";
28✔
1299
        return _server_component_impl->make_command_ack_message(
28✔
1300
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
28✔
1301
    }
1302

1303
    // TODO may need support multi storage id
1304
    _last_storage_id = storage_id;
2✔
1305

1306
    _last_storage_information_command = command;
2✔
1307

1308
    _storage_information_callbacks.queue(
2✔
1309
        storage_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
2✔
1310

1311
    // ack will be sent later in respond_storage_information
1312
    return std::nullopt;
2✔
1313
}
16✔
1314

1315
std::optional<mavlink_command_ack_t>
1316
CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLong& command)
1✔
1317
{
1318
    auto storage_id = static_cast<uint8_t>(command.params.param1);
1✔
1319
    auto format = static_cast<bool>(command.params.param2);
1✔
1320
    auto reset_image_log = static_cast<bool>(command.params.param3);
1✔
1321

1322
    UNUSED(format);
1✔
1323
    UNUSED(reset_image_log);
1✔
1324

1325
    std::lock_guard<std::mutex> lg{_mutex};
1✔
1326

1327
    if (_format_storage_callbacks.empty()) {
1✔
UNCOV
1328
        LogDebug() << "process storage format requested with no storage format subscriber";
×
UNCOV
1329
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1330
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1331
    }
1332

1333
    _last_format_storage_command = command;
1✔
1334

1335
    _format_storage_callbacks.queue(
1✔
1336
        storage_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
1✔
1337

1338
    return std::nullopt;
1✔
1339
}
1✔
1340

UNCOV
1341
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_capture_status_request(
×
1342
    const MavlinkCommandReceiver::CommandLong& command)
1343
{
1344
    auto capture_status = static_cast<bool>(command.params.param1);
×
1345

UNCOV
1346
    if (!capture_status) {
×
1347
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1348
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1349
    }
1350

1351
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1352
    if (_capture_status_callbacks.empty()) {
×
UNCOV
1353
        LogDebug() << "process camera capture status requested with no capture status subscriber";
×
1354
        return _server_component_impl->make_command_ack_message(
×
1355
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1356
    }
1357

1358
    _last_capture_status_command = command;
×
1359

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

1364
    // ack was already sent
1365
    return std::nullopt;
×
UNCOV
1366
}
×
1367

1368
void CameraServerImpl::send_capture_status()
13✔
1369
{
1370
    std::lock_guard<std::mutex> lg{_mutex};
13✔
1371

1372
    uint8_t image_status{};
13✔
1373
    if (_capture_status.image_status ==
13✔
1374
            CameraServer::CaptureStatus::ImageStatus::CaptureInProgress ||
13✔
1375
        _capture_status.image_status ==
13✔
1376
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress) {
UNCOV
1377
        image_status |= StatusFlags::IN_PROGRESS;
×
1378
    }
1379

1380
    if (_capture_status.image_status == CameraServer::CaptureStatus::ImageStatus::IntervalIdle ||
13✔
1381
        _capture_status.image_status ==
13✔
1382
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress ||
13✔
1383
        _is_image_capture_interval_set) {
13✔
1384
        image_status |= StatusFlags::INTERVAL_SET;
3✔
1385
    }
1386

1387
    uint8_t video_status = 0;
13✔
1388
    if (_capture_status.video_status == CameraServer::CaptureStatus::VideoStatus::Idle) {
13✔
1389
        video_status = 0;
13✔
UNCOV
1390
    } else if (
×
UNCOV
1391
        _capture_status.video_status ==
×
1392
        CameraServer::CaptureStatus::VideoStatus::CaptureInProgress) {
1393
        video_status = 1;
×
1394
    }
1395

1396
    const uint32_t recording_time_ms =
13✔
1397
        static_cast<uint32_t>(static_cast<double>(_capture_status.recording_time_s) * 1e3);
13✔
1398
    const float available_capacity = _capture_status.available_capacity_mib;
13✔
1399

1400
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
13✔
1401
        mavlink_message_t message{};
13✔
1402
        mavlink_msg_camera_capture_status_pack_chan(
26✔
1403
            mavlink_address.system_id,
13✔
1404
            mavlink_address.component_id,
13✔
1405
            channel,
1406
            &message,
1407
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
13✔
1408
            image_status,
13✔
1409
            video_status,
13✔
1410
            _image_capture_timer_interval_s,
1411
            recording_time_ms,
13✔
1412
            available_capacity,
13✔
1413
            _image_capture_count,
1414
            0);
1415
        return message;
13✔
1416
    });
1417
}
13✔
1418

1419
std::optional<mavlink_command_ack_t>
1420
CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::CommandLong& command)
1✔
1421
{
1422
    auto reset = static_cast<bool>(command.params.param1);
1✔
1423

1424
    UNUSED(reset);
1✔
1425

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

1428
    if (_reset_settings_callbacks.empty()) {
1✔
UNCOV
1429
        LogDebug() << "reset camera settings requested with no camera settings subscriber";
×
UNCOV
1430
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1431
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1432
    }
1433

1434
    _last_reset_settings_command = command;
1✔
1435
    _reset_settings_callbacks.queue(
1✔
1436
        0, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
1✔
1437

1438
    return std::nullopt;
1✔
1439
}
1✔
1440

1441
std::optional<mavlink_command_ack_t>
1442
CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandLong& command)
2✔
1443
{
1444
    auto camera_mode = static_cast<CAMERA_MODE>(command.params.param2);
2✔
1445

1446
    std::lock_guard<std::mutex> lg{_mutex};
2✔
1447

1448
    if (_set_mode_callbacks.empty()) {
2✔
UNCOV
1449
        LogDebug() << "Set mode requested with no set mode subscriber";
×
UNCOV
1450
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1451
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1452
    }
1453

1454
    // convert camera mode enum type
1455
    CameraServer::Mode convert_camera_mode = CameraServer::Mode::Unknown;
2✔
1456
    if (camera_mode == CAMERA_MODE_IMAGE) {
2✔
1457
        convert_camera_mode = CameraServer::Mode::Photo;
1✔
1458
    } else if (camera_mode == CAMERA_MODE_VIDEO) {
1✔
1459
        convert_camera_mode = CameraServer::Mode::Video;
1✔
1460
    }
1461

1462
    if (convert_camera_mode == CameraServer::Mode::Unknown) {
2✔
UNCOV
1463
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1464
            command, MAV_RESULT::MAV_RESULT_DENIED);
×
1465
    }
1466

1467
    _last_set_mode_command = command;
2✔
1468

1469
    _set_mode_callbacks.queue(convert_camera_mode, [this](const auto& func) {
2✔
1470
        _server_component_impl->call_user_callback(func);
2✔
1471
    });
2✔
1472

1473
    return std::nullopt;
2✔
1474
}
2✔
1475

1476
std::optional<mavlink_command_ack_t>
UNCOV
1477
CameraServerImpl::process_set_camera_zoom(const MavlinkCommandReceiver::CommandLong& command)
×
1478
{
UNCOV
1479
    auto zoom_type = static_cast<CAMERA_ZOOM_TYPE>(command.params.param1);
×
1480
    auto zoom_value = command.params.param2;
×
1481

1482
    std::lock_guard<std::mutex> lg{_mutex};
×
1483

UNCOV
1484
    if (_zoom_in_start_callbacks.empty() && _zoom_out_start_callbacks.empty() &&
×
1485
        _zoom_stop_callbacks.empty() && _zoom_range_callbacks.empty()) {
×
UNCOV
1486
        LogWarn() << "No camera zoom is supported";
×
1487
        return _server_component_impl->make_command_ack_message(
×
1488
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1489
    }
1490

1491
    auto unsupported = [&]() {
×
UNCOV
1492
        LogWarn() << "unsupported set camera zoom type (" << (int)zoom_type << ") request";
×
UNCOV
1493
    };
×
1494

1495
    switch (zoom_type) {
×
1496
        case ZOOM_TYPE_CONTINUOUS:
×
UNCOV
1497
            if (zoom_value == -1.f) {
×
1498
                if (_zoom_out_start_callbacks.empty()) {
×
1499
                    unsupported();
×
1500
                    return _server_component_impl->make_command_ack_message(
×
1501
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1502
                } else {
1503
                    _last_zoom_out_start_command = command;
×
1504
                    int dummy = 0;
×
UNCOV
1505
                    _zoom_out_start_callbacks.queue(dummy, [this](const auto& func) {
×
1506
                        _server_component_impl->call_user_callback(func);
×
1507
                    });
×
1508
                }
1509
            } else if (zoom_value == 1.f) {
×
1510
                if (_zoom_in_start_callbacks.empty()) {
×
UNCOV
1511
                    unsupported();
×
1512
                    return _server_component_impl->make_command_ack_message(
×
1513
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1514
                } else {
1515
                    _last_zoom_in_start_command = command;
×
1516
                    int dummy = 0;
×
UNCOV
1517
                    _zoom_in_start_callbacks.queue(dummy, [this](const auto& func) {
×
1518
                        _server_component_impl->call_user_callback(func);
×
1519
                    });
×
1520
                }
1521
            } else if (zoom_value == 0.f) {
×
1522
                if (_zoom_stop_callbacks.empty()) {
×
UNCOV
1523
                    unsupported();
×
1524
                    return _server_component_impl->make_command_ack_message(
×
1525
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1526
                } else {
1527
                    _last_zoom_stop_command = command;
×
1528
                    int dummy = 0;
×
UNCOV
1529
                    _zoom_stop_callbacks.queue(dummy, [this](const auto& func) {
×
1530
                        _server_component_impl->call_user_callback(func);
×
1531
                    });
×
1532
                }
1533
            } else {
1534
                LogWarn() << "Invalid zoom value";
×
UNCOV
1535
                return _server_component_impl->make_command_ack_message(
×
UNCOV
1536
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1537
            }
1538
            break;
×
1539
        case ZOOM_TYPE_RANGE:
×
UNCOV
1540
            if (_zoom_range_callbacks.empty()) {
×
1541
                unsupported();
×
1542
                return _server_component_impl->make_command_ack_message(
×
1543
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1544

1545
            } else {
1546
                _last_zoom_range_command = command;
×
UNCOV
1547
                _zoom_range_callbacks.queue(zoom_value, [this](const auto& func) {
×
UNCOV
1548
                    _server_component_impl->call_user_callback(func);
×
1549
                });
×
1550
            }
1551
            break;
×
1552
        case ZOOM_TYPE_STEP:
×
1553
        // Fallthrough
1554
        case ZOOM_TYPE_FOCAL_LENGTH:
1555
        // Fallthrough
1556
        case ZOOM_TYPE_HORIZONTAL_FOV:
1557
        // Fallthrough
1558
        default:
UNCOV
1559
            unsupported();
×
UNCOV
1560
            return _server_component_impl->make_command_ack_message(
×
UNCOV
1561
                command, MAV_RESULT::MAV_RESULT_DENIED);
×
1562
            break;
1563
    }
1564

1565
    // For any success so far, we don't ack yet, but later when the respond function is called.
UNCOV
1566
    return std::nullopt;
×
UNCOV
1567
}
×
1568

1569
std::optional<mavlink_command_ack_t>
1570
CameraServerImpl::process_set_camera_focus(const MavlinkCommandReceiver::CommandLong& command)
×
1571
{
UNCOV
1572
    auto focus_type = static_cast<SET_FOCUS_TYPE>(command.params.param1);
×
1573
    auto focus_value = command.params.param2;
×
1574

1575
    UNUSED(focus_type);
×
1576
    UNUSED(focus_value);
×
1577

1578
    LogDebug() << "unsupported set camera focus request";
×
1579

UNCOV
1580
    return _server_component_impl->make_command_ack_message(
×
1581
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1582
}
1583

1584
std::optional<mavlink_command_ack_t>
UNCOV
1585
CameraServerImpl::process_set_storage_usage(const MavlinkCommandReceiver::CommandLong& command)
×
1586
{
UNCOV
1587
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
1588
    auto usage = static_cast<STORAGE_USAGE_FLAG>(command.params.param2);
×
1589

1590
    UNUSED(storage_id);
×
1591
    UNUSED(usage);
×
1592

1593
    LogDebug() << "unsupported set storage usage request";
×
1594

UNCOV
1595
    return _server_component_impl->make_command_ack_message(
×
1596
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1597
}
1598

1599
std::optional<mavlink_command_ack_t>
1600
CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command)
2✔
1601
{
1602
    auto interval_s = command.params.param2;
2✔
1603
    auto total_images = static_cast<int32_t>(command.params.param3);
2✔
1604
    auto seq_number = static_cast<int32_t>(command.params.param4);
2✔
1605

1606
    LogDebug() << "received image start capture request - interval: " << +interval_s
6✔
1607
               << " total: " << +total_images << " index: " << +seq_number;
6✔
1608

1609
    // TODO: validate parameters and return MAV_RESULT_DENIED not valid
1610

1611
    stop_image_capture_interval();
2✔
1612

1613
    std::lock_guard<std::mutex> lg{_mutex};
2✔
1614

1615
    if (_take_photo_callbacks.empty()) {
2✔
UNCOV
1616
        LogDebug() << "image capture requested with no take photo subscriber";
×
UNCOV
1617
        return _server_component_impl->make_command_ack_message(
×
UNCOV
1618
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1619
    }
1620

1621
    // single image capture
1622
    if (total_images == 1) {
2✔
1623
        // MAV_RESULT_ACCEPTED must be sent before CAMERA_IMAGE_CAPTURED
1624
        auto command_ack = _server_component_impl->make_command_ack_message(
1✔
1625
            command, MAV_RESULT::MAV_RESULT_IN_PROGRESS);
1626
        _server_component_impl->send_command_ack(command_ack);
1✔
1627

1628
        _last_take_photo_command = command;
1✔
1629

1630
        _take_photo_callbacks.queue(seq_number, [this](const auto& func) {
1✔
1631
            _server_component_impl->call_user_callback(func);
1✔
1632
        });
1✔
1633

1634
        return std::nullopt;
1✔
1635
    }
1636

1637
    start_image_capture_interval(interval_s, total_images, seq_number);
1✔
1638

1639
    return _server_component_impl->make_command_ack_message(
2✔
1640
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
2✔
1641
}
2✔
1642

1643
std::optional<mavlink_command_ack_t>
1644
CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
1✔
1645
{
1646
    LogDebug() << "received image stop capture request";
1✔
1647

1648
    // REVISIT: should we return something other that MAV_RESULT_ACCEPTED if
1649
    // there is not currently a capture interval active?
1650
    stop_image_capture_interval();
1✔
1651

1652
    return _server_component_impl->make_command_ack_message(
2✔
1653
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
2✔
1654
}
1655

UNCOV
1656
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_image_capture_request(
×
1657
    const MavlinkCommandReceiver::CommandLong& command)
1658
{
1659
    auto seq_number = static_cast<uint32_t>(command.params.param1);
×
1660

UNCOV
1661
    UNUSED(seq_number);
×
1662

UNCOV
1663
    LogDebug() << "unsupported image capture request";
×
1664

UNCOV
1665
    return _server_component_impl->make_command_ack_message(
×
1666
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1667
}
1668

1669
std::optional<mavlink_command_ack_t>
UNCOV
1670
CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1671
{
UNCOV
1672
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1673
    auto status_frequency = command.params.param2;
×
1674

1675
    UNUSED(status_frequency);
×
1676

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

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

1685
    _last_start_video_command = command;
×
UNCOV
1686
    _start_video_callbacks.queue(
×
UNCOV
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_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1694
{
UNCOV
1695
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1696

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

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

1705
    _last_stop_video_command = command;
×
UNCOV
1706
    _stop_video_callbacks.queue(
×
UNCOV
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_start_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1714
{
UNCOV
1715
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1716

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

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

1725
    _last_start_video_streaming_command = command;
×
UNCOV
1726
    _start_video_streaming_callbacks.queue(
×
UNCOV
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>
1733
CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1734
{
UNCOV
1735
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1736

UNCOV
1737
    std::lock_guard<std::mutex> lg{_mutex};
×
1738

UNCOV
1739
    if (_stop_video_streaming_callbacks.empty()) {
×
1740
        LogDebug() << "video stop streaming requested with no video stop streaming subscriber";
×
UNCOV
1741
        return _server_component_impl->make_command_ack_message(
×
1742
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1743
    }
1744

1745
    _last_stop_video_streaming_command = command;
×
UNCOV
1746
    _stop_video_streaming_callbacks.queue(
×
UNCOV
1747
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1748

1749
    return std::nullopt;
×
1750
}
×
1751

1752
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_information_request(
15✔
1753
    const MavlinkCommandReceiver::CommandLong& command)
1754
{
1755
    auto stream_id = static_cast<uint8_t>(command.params.param1);
15✔
1756

1757
    UNUSED(stream_id);
15✔
1758

1759
    std::lock_guard<std::mutex> lg{_mutex};
15✔
1760

1761
    if (_is_video_streaming_set) {
15✔
1762
        auto command_ack = _server_component_impl->make_command_ack_message(
1✔
1763
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
1764
        _server_component_impl->send_command_ack(command_ack);
1✔
1765
        LogDebug() << "sent video streaming ack";
1✔
1766

1767
        const char name[32] = "";
1✔
1768

1769
        _video_streaming.rtsp_uri.resize(sizeof(mavlink_video_stream_information_t::uri));
1✔
1770

1771
        mavlink_message_t msg{};
1✔
1772
        mavlink_msg_video_stream_information_pack(
2✔
1773
            _server_component_impl->get_own_system_id(),
1✔
1774
            _server_component_impl->get_own_component_id(),
1✔
1775
            &msg,
1776
            0, // Stream id
1777
            0, // Count
1778
            VIDEO_STREAM_TYPE_RTSP,
1779
            VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1780
            0, // famerate
1781
            0, // resolution horizontal
1782
            0, // resolution vertical
1783
            0, // bitrate
1784
            0, // rotation
1785
            0, // horizontal field of view
1786
            name,
1787
            _video_streaming.rtsp_uri.c_str(),
1788
            0,
1789
            0);
1790

1791
        _server_component_impl->send_message(msg);
1✔
1792

1793
        // Ack already sent.
1794
        return std::nullopt;
1✔
1795

1796
    } else {
1797
        return _server_component_impl->make_command_ack_message(
28✔
1798
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
28✔
1799
    }
1800
}
15✔
1801

1802
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_status_request(
17✔
1803
    const MavlinkCommandReceiver::CommandLong& command)
1804
{
1805
    auto stream_id = static_cast<uint8_t>(command.params.param1);
17✔
1806

1807
    UNUSED(stream_id);
17✔
1808

1809
    std::lock_guard<std::mutex> lg{_mutex};
17✔
1810

1811
    if (!_is_video_streaming_set) {
17✔
1812
        return _server_component_impl->make_command_ack_message(
32✔
1813
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
32✔
1814
    }
1815

1816
    auto command_ack =
1✔
1817
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
1✔
1818
    _server_component_impl->send_command_ack(command_ack);
1✔
1819
    LogDebug() << "sent video streaming ack";
1✔
1820

1821
    mavlink_message_t msg{};
1✔
1822
    mavlink_msg_video_stream_status_pack(
1✔
1823
        _server_component_impl->get_own_system_id(),
1✔
1824
        _server_component_impl->get_own_component_id(),
1✔
1825
        &msg,
1826
        0, // Stream id
1827
        VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1828
        0, // framerate
1829
        0, // resolution horizontal
1830
        0, // resolution vertical
1831
        0, // bitrate
1832
        0, // rotation
1833
        0, // horizontal field of view
1834
        0);
1835
    _server_component_impl->send_message(msg);
1✔
1836

1837
    // ack was already sent
1838
    return std::nullopt;
1✔
1839
}
17✔
1840

1841
CameraServer::ZoomInStartHandle
UNCOV
1842
CameraServerImpl::subscribe_zoom_in_start(const CameraServer::ZoomInStartCallback& callback)
×
1843
{
UNCOV
1844
    std::lock_guard<std::mutex> lg{_mutex};
×
1845
    return _zoom_in_start_callbacks.subscribe(callback);
×
UNCOV
1846
}
×
1847

1848
void CameraServerImpl::unsubscribe_zoom_in_start(CameraServer::ZoomInStartHandle handle)
×
1849
{
UNCOV
1850
    std::lock_guard<std::mutex> lg{_mutex};
×
1851
    _zoom_in_start_callbacks.unsubscribe(handle);
×
UNCOV
1852
}
×
1853

1854
CameraServer::Result
1855
CameraServerImpl::respond_zoom_in_start(CameraServer::CameraFeedback zoom_in_start_feedback)
×
1856
{
UNCOV
1857
    std::lock_guard<std::mutex> lg{_mutex};
×
1858

UNCOV
1859
    switch (zoom_in_start_feedback) {
×
1860
        default:
×
1861
            // Fallthrough
1862
        case CameraServer::CameraFeedback::Unknown:
1863
            return CameraServer::Result::Error;
×
UNCOV
1864
        case CameraServer::CameraFeedback::Ok: {
×
UNCOV
1865
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1866
                _last_zoom_in_start_command, MAV_RESULT_ACCEPTED);
×
1867
            _server_component_impl->send_command_ack(command_ack);
×
1868
            return CameraServer::Result::Success;
×
1869
        }
1870
        case CameraServer::CameraFeedback::Busy: {
×
1871
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1872
                _last_zoom_in_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1873
            _server_component_impl->send_command_ack(command_ack);
×
1874
            return CameraServer::Result::Success;
×
1875
        }
1876
        case CameraServer::CameraFeedback::Failed: {
×
1877
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1878
                _last_zoom_in_start_command, MAV_RESULT_FAILED);
×
1879
            _server_component_impl->send_command_ack(command_ack);
×
1880
            return CameraServer::Result::Success;
×
1881
        }
1882
    }
1883
}
×
1884

1885
CameraServer::ZoomOutStartHandle
1886
CameraServerImpl::subscribe_zoom_out_start(const CameraServer::ZoomOutStartCallback& callback)
×
1887
{
UNCOV
1888
    std::lock_guard<std::mutex> lg{_mutex};
×
1889
    return _zoom_out_start_callbacks.subscribe(callback);
×
UNCOV
1890
}
×
1891

1892
void CameraServerImpl::unsubscribe_zoom_out_start(CameraServer::ZoomOutStartHandle handle)
×
1893
{
UNCOV
1894
    std::lock_guard<std::mutex> lg{_mutex};
×
1895
    _zoom_out_start_callbacks.unsubscribe(handle);
×
UNCOV
1896
}
×
1897

1898
CameraServer::Result
1899
CameraServerImpl::respond_zoom_out_start(CameraServer::CameraFeedback zoom_out_start_feedback)
×
1900
{
UNCOV
1901
    std::lock_guard<std::mutex> lg{_mutex};
×
1902

UNCOV
1903
    switch (zoom_out_start_feedback) {
×
1904
        default:
×
1905
            // Fallthrough
1906
        case CameraServer::CameraFeedback::Unknown:
1907
            return CameraServer::Result::Error;
×
UNCOV
1908
        case CameraServer::CameraFeedback::Ok: {
×
UNCOV
1909
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1910
                _last_zoom_out_start_command, MAV_RESULT_ACCEPTED);
×
1911
            _server_component_impl->send_command_ack(command_ack);
×
1912
            return CameraServer::Result::Success;
×
1913
        }
1914
        case CameraServer::CameraFeedback::Busy: {
×
1915
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1916
                _last_zoom_out_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1917
            _server_component_impl->send_command_ack(command_ack);
×
1918
            return CameraServer::Result::Success;
×
1919
        }
1920
        case CameraServer::CameraFeedback::Failed: {
×
1921
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1922
                _last_zoom_out_start_command, MAV_RESULT_FAILED);
×
1923
            _server_component_impl->send_command_ack(command_ack);
×
1924
            return CameraServer::Result::Success;
×
1925
        }
1926
    }
1927
}
×
1928

1929
CameraServer::ZoomStopHandle
1930
CameraServerImpl::subscribe_zoom_stop(const CameraServer::ZoomStopCallback& callback)
×
1931
{
UNCOV
1932
    std::lock_guard<std::mutex> lg{_mutex};
×
1933
    return _zoom_stop_callbacks.subscribe(callback);
×
UNCOV
1934
}
×
1935

1936
void CameraServerImpl::unsubscribe_zoom_stop(CameraServer::ZoomStopHandle handle)
×
1937
{
UNCOV
1938
    std::lock_guard<std::mutex> lg{_mutex};
×
1939
    _zoom_stop_callbacks.unsubscribe(handle);
×
UNCOV
1940
}
×
1941

1942
CameraServer::Result
1943
CameraServerImpl::respond_zoom_stop(CameraServer::CameraFeedback zoom_stop_feedback)
×
1944
{
UNCOV
1945
    std::lock_guard<std::mutex> lg{_mutex};
×
1946

UNCOV
1947
    switch (zoom_stop_feedback) {
×
1948
        default:
×
1949
            // Fallthrough
1950
        case CameraServer::CameraFeedback::Unknown:
1951
            return CameraServer::Result::Error;
×
UNCOV
1952
        case CameraServer::CameraFeedback::Ok: {
×
UNCOV
1953
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1954
                _last_zoom_stop_command, MAV_RESULT_ACCEPTED);
×
1955
            _server_component_impl->send_command_ack(command_ack);
×
1956
            return CameraServer::Result::Success;
×
1957
        }
1958
        case CameraServer::CameraFeedback::Busy: {
×
1959
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1960
                _last_zoom_stop_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1961
            _server_component_impl->send_command_ack(command_ack);
×
1962
            return CameraServer::Result::Success;
×
1963
        }
1964
        case CameraServer::CameraFeedback::Failed: {
×
1965
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
1966
                _last_zoom_stop_command, MAV_RESULT_FAILED);
×
1967
            _server_component_impl->send_command_ack(command_ack);
×
1968
            return CameraServer::Result::Success;
×
1969
        }
1970
    }
1971
}
×
1972

1973
CameraServer::ZoomRangeHandle
1974
CameraServerImpl::subscribe_zoom_range(const CameraServer::ZoomRangeCallback& callback)
×
1975
{
UNCOV
1976
    std::lock_guard<std::mutex> lg{_mutex};
×
1977
    return _zoom_range_callbacks.subscribe(callback);
×
UNCOV
1978
}
×
1979

1980
void CameraServerImpl::unsubscribe_zoom_range(CameraServer::ZoomRangeHandle handle)
×
1981
{
UNCOV
1982
    std::lock_guard<std::mutex> lg{_mutex};
×
1983
    _zoom_range_callbacks.unsubscribe(handle);
×
UNCOV
1984
}
×
1985

1986
CameraServer::Result
1987
CameraServerImpl::respond_zoom_range(CameraServer::CameraFeedback zoom_range_feedback)
×
1988
{
UNCOV
1989
    std::lock_guard<std::mutex> lg{_mutex};
×
1990

UNCOV
1991
    switch (zoom_range_feedback) {
×
1992
        case CameraServer::CameraFeedback::Ok: {
×
UNCOV
1993
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1994
                _last_zoom_range_command, MAV_RESULT_ACCEPTED);
×
1995
            _server_component_impl->send_command_ack(command_ack);
×
1996
            return CameraServer::Result::Success;
×
1997
        }
1998
        case CameraServer::CameraFeedback::Busy: {
×
1999
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
2000
                _last_zoom_range_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
2001
            _server_component_impl->send_command_ack(command_ack);
×
2002
            return CameraServer::Result::Success;
×
2003
        }
2004
        case CameraServer::CameraFeedback::Failed: {
×
2005
            auto command_ack = _server_component_impl->make_command_ack_message(
×
UNCOV
2006
                _last_zoom_range_command, MAV_RESULT_FAILED);
×
2007
            _server_component_impl->send_command_ack(command_ack);
×
2008
            return CameraServer::Result::Success;
×
2009
        }
2010
        case CameraServer::CameraFeedback::Unknown:
×
2011
            // Fallthrough
2012
        default:
2013
            return CameraServer::Result::Error;
×
2014
    }
UNCOV
2015
}
×
2016

2017
std::optional<mavlink_command_ack_t>
2018
CameraServerImpl::process_track_point_command(const MavlinkCommandReceiver::CommandLong& command)
×
2019
{
UNCOV
2020
    if (!is_command_sender_ok(command)) {
×
2021
        LogWarn() << "Incoming track point command is for target sysid "
×
UNCOV
2022
                  << int(command.target_system_id) << " instead of "
×
2023
                  << int(_server_component_impl->get_own_system_id());
×
2024
        return std::nullopt;
×
2025
    }
2026

2027
    std::lock_guard<std::mutex> lg{_mutex};
×
2028

UNCOV
2029
    if (_tracking_point_callbacks.empty()) {
×
2030
        LogDebug() << "Track point requested with no user callback provided";
×
UNCOV
2031
        return _server_component_impl->make_command_ack_message(
×
2032
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
2033
    }
2034

2035
    CameraServer::TrackPoint track_point{
×
UNCOV
2036
        command.params.param1, command.params.param2, command.params.param3};
×
2037

2038
    _last_track_point_command = command;
×
2039
    _tracking_point_callbacks.queue(track_point, [this](const auto& func) {
×
UNCOV
2040
        _server_component_impl->call_user_callback(func);
×
2041
    });
×
2042
    // We don't send an ack but leave that to the user.
2043
    return std::nullopt;
×
2044
}
×
2045

2046
std::optional<mavlink_command_ack_t> CameraServerImpl::process_track_rectangle_command(
×
2047
    const MavlinkCommandReceiver::CommandLong& command)
2048
{
2049
    if (!is_command_sender_ok(command)) {
×
UNCOV
2050
        LogWarn() << "Incoming track rectangle command is for target sysid "
×
UNCOV
2051
                  << int(command.target_system_id) << " instead of "
×
2052
                  << int(_server_component_impl->get_own_system_id());
×
2053
        return std::nullopt;
×
2054
    }
2055

2056
    std::lock_guard<std::mutex> lg{_mutex};
×
2057

UNCOV
2058
    if (_tracking_rectangle_callbacks.empty()) {
×
2059
        LogDebug() << "Track rectangle requested with no user callback provided";
×
UNCOV
2060
        return _server_component_impl->make_command_ack_message(
×
2061
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
2062
    }
2063

2064
    CameraServer::TrackRectangle track_rectangle{
×
UNCOV
2065
        command.params.param1, command.params.param2, command.params.param3, command.params.param4};
×
2066

2067
    _last_track_rectangle_command = command;
×
2068
    _tracking_rectangle_callbacks.queue(track_rectangle, [this](const auto& func) {
×
UNCOV
2069
        _server_component_impl->call_user_callback(func);
×
2070
    });
×
2071
    // We don't send an ack but leave that to the user.
2072
    return std::nullopt;
×
2073
}
×
2074

2075
std::optional<mavlink_command_ack_t>
2076
CameraServerImpl::process_track_off_command(const MavlinkCommandReceiver::CommandLong& command)
×
2077
{
UNCOV
2078
    if (!is_command_sender_ok(command)) {
×
2079
        LogWarn() << "Incoming track off command is for target sysid "
×
UNCOV
2080
                  << int(command.target_system_id) << " instead of "
×
2081
                  << int(_server_component_impl->get_own_system_id());
×
2082
        return std::nullopt;
×
2083
    }
2084

2085
    std::lock_guard<std::mutex> lg{_mutex};
×
2086

UNCOV
2087
    if (_tracking_off_callbacks.empty()) {
×
2088
        LogDebug() << "Tracking off requested with no user callback provided";
×
UNCOV
2089
        return _server_component_impl->make_command_ack_message(
×
2090
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
2091
    }
2092

2093
    _last_tracking_off_command = command;
×
UNCOV
2094
    _tracking_off_callbacks.queue(
×
UNCOV
2095
        0, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
2096
    // We don't send an ack but leave that to the user.
2097
    return std::nullopt;
×
2098
}
×
2099

2100
std::optional<mavlink_command_ack_t>
2101
CameraServerImpl::process_set_message_interval(const MavlinkCommandReceiver::CommandLong& command)
×
2102
{
UNCOV
2103
    if (!is_command_sender_ok(command)) {
×
2104
        LogWarn() << "Incoming track off command is for target sysid "
×
UNCOV
2105
                  << int(command.target_system_id) << " instead of "
×
2106
                  << int(_server_component_impl->get_own_system_id());
×
2107
        return std::nullopt;
×
2108
    }
2109

2110
    auto message_id = static_cast<uint32_t>(command.params.param1);
×
UNCOV
2111
    auto interval_us = static_cast<int32_t>(command.params.param2);
×
UNCOV
2112
    UNUSED(message_id);
×
2113

2114
    // Interval value of -1 means to disable sending messages
2115
    if (interval_us < 0) {
×
UNCOV
2116
        stop_sending_tracking_status();
×
2117
    } else {
2118
        start_sending_tracking_status(interval_us);
×
2119
    }
2120

2121
    // Always send the "Accepted" result
UNCOV
2122
    return _server_component_impl->make_command_ack_message(
×
UNCOV
2123
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
2124
}
2125

2126
void CameraServerImpl::send_tracking_status_with_interval(uint32_t interval_us)
×
2127
{
2128
    while (true) {
2129
        std::this_thread::sleep_for(std::chrono::microseconds{interval_us});
×
2130
        {
UNCOV
2131
            std::scoped_lock lg{_mutex};
×
2132
            if (!_sending_tracking_status) {
×
UNCOV
2133
                return;
×
2134
            }
2135
        }
×
2136
        _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
2137
            mavlink_message_t message;
2138
            std::lock_guard<std::mutex> lg{_mutex};
×
2139

2140
            // The message is filled based on current tracking mode
2141
            switch (_tracking_mode) {
×
UNCOV
2142
                default:
×
2143
                    // Fallthrough
2144
                case TrackingMode::NONE:
2145

UNCOV
2146
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
UNCOV
2147
                        mavlink_address.system_id,
×
UNCOV
2148
                        mavlink_address.component_id,
×
2149
                        channel,
2150
                        &message,
2151
                        CAMERA_TRACKING_STATUS_FLAGS_IDLE,
2152
                        CAMERA_TRACKING_MODE_NONE,
2153
                        CAMERA_TRACKING_TARGET_DATA_NONE,
2154
                        0.0f,
2155
                        0.0f,
2156
                        0.0f,
2157
                        0.0f,
2158
                        0.0f,
2159
                        0.0f,
2160
                        0.0f,
2161
                        0);
UNCOV
2162
                    break;
×
UNCOV
2163
                case TrackingMode::POINT:
×
2164

2165
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
2166
                        mavlink_address.system_id,
×
UNCOV
2167
                        mavlink_address.component_id,
×
2168
                        channel,
2169
                        &message,
2170
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
2171
                        CAMERA_TRACKING_MODE_POINT,
2172
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
2173
                        _tracked_point.point_x,
2174
                        _tracked_point.point_y,
2175
                        _tracked_point.radius,
2176
                        0.0f,
2177
                        0.0f,
2178
                        0.0f,
2179
                        0.0f,
2180
                        0);
UNCOV
2181
                    break;
×
2182

UNCOV
2183
                case TrackingMode::RECTANGLE:
×
2184

UNCOV
2185
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
2186
                        mavlink_address.system_id,
×
UNCOV
2187
                        mavlink_address.component_id,
×
2188
                        channel,
2189
                        &message,
2190
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
2191
                        CAMERA_TRACKING_MODE_RECTANGLE,
2192
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
2193
                        0.0f,
2194
                        0.0f,
2195
                        0.0f,
2196
                        _tracked_rectangle.top_left_corner_x,
2197
                        _tracked_rectangle.top_left_corner_y,
2198
                        _tracked_rectangle.bottom_right_corner_x,
2199
                        _tracked_rectangle.bottom_right_corner_y,
2200
                        0);
UNCOV
2201
                    break;
×
2202
            }
UNCOV
2203
            return message;
×
2204
        });
×
UNCOV
2205
    }
×
2206
}
2207

2208
void CameraServerImpl::start_sending_tracking_status(uint32_t interval_ms)
×
2209
{
2210
    // Stop sending status with the old interval
2211
    stop_sending_tracking_status();
×
2212

UNCOV
2213
    std::lock_guard<std::mutex> lg{_mutex};
×
2214
    _sending_tracking_status = true;
×
UNCOV
2215
    _tracking_status_sending_thread =
×
2216
        std::thread{&CameraServerImpl::send_tracking_status_with_interval, this, interval_ms};
×
2217
}
×
2218

2219
void CameraServerImpl::stop_sending_tracking_status()
×
2220
{
2221
    // Firstly, ask the other thread to stop sending the status
2222
    {
UNCOV
2223
        std::scoped_lock lg{_mutex};
×
UNCOV
2224
        _sending_tracking_status = false;
×
UNCOV
2225
    }
×
2226
    // If the thread was active, wait for it to finish
2227
    if (_tracking_status_sending_thread.joinable()) {
×
2228
        _tracking_status_sending_thread.join();
×
2229
    }
2230
}
×
2231

UNCOV
2232
void CameraServerImpl::start_sending_capture_status()
×
2233
{
UNCOV
2234
    _capture_status_timer_cookie = _server_component_impl->add_call_every(
×
NEW
2235
        [this]() { send_capture_status(); }, CAPTURE_STATUS_INTERVAL_S);
×
NEW
2236
}
×
2237

2238
void CameraServerImpl::stop_sending_capture_status()
9✔
2239
{
2240
    _server_component_impl->remove_call_every(_capture_status_timer_cookie);
9✔
2241
}
9✔
2242

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