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

mavlink / MAVSDK / 14846374211

05 May 2025 09:13PM UTC coverage: 44.218% (+0.1%) from 44.075%
14846374211

push

github

web-flow
Merge pull request #2542 from mavlink/pr-tsan

Fixing thread sanitizer issues

229 of 320 new or added lines in 20 files covered. (71.56%)

73 existing lines in 8 files now uncovered.

14784 of 33434 relevant lines covered (44.22%)

276.78 hits per line

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

37.14
/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) {
40✔
26
            return process_request_message(command);
40✔
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) {
5✔
38
            return process_camera_settings_request(command);
5✔
39
        },
40
        this);
41
    _server_component_impl->register_mavlink_command_handler(
9✔
42
        MAV_CMD_REQUEST_STORAGE_INFORMATION,
43
        [this](const MavlinkCommandReceiver::CommandLong& command) {
9✔
44
            return process_storage_information_request(command);
9✔
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) {
1✔
134
            return process_video_stream_information_request(command);
1✔
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) {
6✔
140
            return process_video_stream_status_request(command);
6✔
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
    _server_component_impl->unregister_all_mavlink_command_handlers(this);
9✔
175

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

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

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

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

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

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

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

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

239
        return true;
×
240
    }
241

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

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

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

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

253
    return true;
18✔
254
}
255

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

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

266
    // TODO: validate information.definition_file_uri
267

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

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

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

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

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

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

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

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

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

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

308
CameraServer::Result CameraServerImpl::respond_take_photo(
4✔
309
    CameraServer::CameraFeedback take_photo_feedback, CameraServer::CaptureInfo capture_info)
310
{
311
    std::lock_guard<std::mutex> lg{_mutex};
4✔
312

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

324
        _image_capture_count = capture_info.index;
4✔
325
    }
326

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

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

354
        case CameraServer::CameraFeedback::Failed: {
×
355
            auto command_ack = _server_component_impl->make_command_ack_message(
×
356
                _last_take_photo_command, MAV_RESULT_FAILED);
×
357
            _server_component_impl->send_command_ack(command_ack);
×
358
            return CameraServer::Result::Success;
×
359
        }
360
    }
361

362
    // REVISIT: Should we cache all CaptureInfo in memory for single image
363
    // captures so that we can respond to requests for lost CAMERA_IMAGE_CAPTURED
364
    // messages without calling back to user code?
365

366
    static const uint8_t camera_id = 0; // deprecated unused field
367

368
    const float attitude_quaternion[] = {
4✔
369
        capture_info.attitude_quaternion.w,
4✔
370
        capture_info.attitude_quaternion.x,
4✔
371
        capture_info.attitude_quaternion.y,
4✔
372
        capture_info.attitude_quaternion.z,
4✔
373
    };
4✔
374

375
    // There needs to be enough data to be copied mavlink internal.
376
    capture_info.file_url.resize(205);
4✔
377

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

401
    return CameraServer::Result::Success;
4✔
402
}
4✔
403

404
CameraServer::StartVideoHandle
405
CameraServerImpl::subscribe_start_video(const CameraServer::StartVideoCallback& callback)
×
406
{
NEW
407
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
408
    return _start_video_callbacks.subscribe(callback);
×
UNCOV
409
}
×
410

411
void CameraServerImpl::unsubscribe_start_video(CameraServer::StartVideoHandle handle)
×
412
{
NEW
413
    std::lock_guard<std::mutex> lg{_mutex};
×
414
    _start_video_callbacks.unsubscribe(handle);
×
415
}
×
416

417
CameraServer::Result
418
CameraServerImpl::respond_start_video(CameraServer::CameraFeedback start_video_feedback)
×
419
{
NEW
420
    std::lock_guard<std::mutex> lg{_mutex};
×
421

422
    switch (start_video_feedback) {
×
423
        default:
×
424
            // Fallthrough
425
        case CameraServer::CameraFeedback::Unknown:
426
            return CameraServer::Result::Error;
×
427
        case CameraServer::CameraFeedback::Ok: {
×
428
            auto command_ack = _server_component_impl->make_command_ack_message(
×
429
                _last_start_video_command, MAV_RESULT_ACCEPTED);
×
430
            _server_component_impl->send_command_ack(command_ack);
×
431
            return CameraServer::Result::Success;
×
432
        }
433
        case CameraServer::CameraFeedback::Busy: {
×
434
            auto command_ack = _server_component_impl->make_command_ack_message(
×
435
                _last_start_video_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
436
            _server_component_impl->send_command_ack(command_ack);
×
437
            return CameraServer::Result::Success;
×
438
        }
439
        case CameraServer::CameraFeedback::Failed: {
×
440
            auto command_ack = _server_component_impl->make_command_ack_message(
×
441
                _last_start_video_command, MAV_RESULT_FAILED);
×
442
            _server_component_impl->send_command_ack(command_ack);
×
443
            return CameraServer::Result::Success;
×
444
        }
445
    }
UNCOV
446
}
×
447

448
CameraServer::StopVideoHandle
449
CameraServerImpl::subscribe_stop_video(const CameraServer::StopVideoCallback& callback)
×
450
{
NEW
451
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
452
    return _stop_video_callbacks.subscribe(callback);
×
UNCOV
453
}
×
454

455
void CameraServerImpl::unsubscribe_stop_video(CameraServer::StopVideoHandle handle)
×
456
{
NEW
457
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
458
    return _stop_video_callbacks.unsubscribe(handle);
×
UNCOV
459
}
×
460

461
CameraServer::Result
462
CameraServerImpl::respond_stop_video(CameraServer::CameraFeedback stop_video_feedback)
×
463
{
NEW
464
    std::lock_guard<std::mutex> lg{_mutex};
×
465

466
    switch (stop_video_feedback) {
×
467
        default:
×
468
            // Fallthrough
469
        case CameraServer::CameraFeedback::Unknown:
470
            return CameraServer::Result::Error;
×
471
        case CameraServer::CameraFeedback::Ok: {
×
472
            auto command_ack = _server_component_impl->make_command_ack_message(
×
473
                _last_stop_video_command, MAV_RESULT_ACCEPTED);
×
474
            _server_component_impl->send_command_ack(command_ack);
×
475
            return CameraServer::Result::Success;
×
476
        }
477
        case CameraServer::CameraFeedback::Busy: {
×
478
            auto command_ack = _server_component_impl->make_command_ack_message(
×
479
                _last_stop_video_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
480
            _server_component_impl->send_command_ack(command_ack);
×
481
            return CameraServer::Result::Success;
×
482
        }
483
        case CameraServer::CameraFeedback::Failed: {
×
484
            auto command_ack = _server_component_impl->make_command_ack_message(
×
485
                _last_stop_video_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
486
            _server_component_impl->send_command_ack(command_ack);
×
487
            return CameraServer::Result::Success;
×
488
        }
489
    }
UNCOV
490
}
×
491

492
CameraServer::StartVideoStreamingHandle CameraServerImpl::subscribe_start_video_streaming(
×
493
    const CameraServer::StartVideoStreamingCallback& callback)
494
{
NEW
495
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
496
    return _start_video_streaming_callbacks.subscribe(callback);
×
UNCOV
497
}
×
498

499
void CameraServerImpl::unsubscribe_start_video_streaming(
×
500
    CameraServer::StartVideoStreamingHandle handle)
501
{
NEW
502
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
503
    return _start_video_streaming_callbacks.unsubscribe(handle);
×
UNCOV
504
}
×
505

506
CameraServer::Result CameraServerImpl::respond_start_video_streaming(
×
507
    CameraServer::CameraFeedback start_video_streaming_feedback)
508
{
NEW
509
    std::lock_guard<std::mutex> lg{_mutex};
×
510

511
    switch (start_video_streaming_feedback) {
×
512
        default:
×
513
            // Fallthrough
514
        case CameraServer::CameraFeedback::Unknown:
515
            return CameraServer::Result::Error;
×
516
        case CameraServer::CameraFeedback::Ok: {
×
517
            auto command_ack = _server_component_impl->make_command_ack_message(
×
518
                _last_start_video_streaming_command, MAV_RESULT_ACCEPTED);
×
519
            _server_component_impl->send_command_ack(command_ack);
×
520
            return CameraServer::Result::Success;
×
521
        }
522
        case CameraServer::CameraFeedback::Busy: {
×
523
            auto command_ack = _server_component_impl->make_command_ack_message(
×
524
                _last_start_video_streaming_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
525
            _server_component_impl->send_command_ack(command_ack);
×
526
            return CameraServer::Result::Success;
×
527
        }
528
        case CameraServer::CameraFeedback::Failed: {
×
529
            auto command_ack = _server_component_impl->make_command_ack_message(
×
530
                _last_start_video_streaming_command, MAV_RESULT_FAILED);
×
531
            _server_component_impl->send_command_ack(command_ack);
×
532
            return CameraServer::Result::Success;
×
533
        }
534
    }
UNCOV
535
}
×
536

537
CameraServer::StopVideoStreamingHandle CameraServerImpl::subscribe_stop_video_streaming(
×
538
    const CameraServer::StopVideoStreamingCallback& callback)
539
{
NEW
540
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
541
    return _stop_video_streaming_callbacks.subscribe(callback);
×
UNCOV
542
}
×
543

544
void CameraServerImpl::unsubscribe_stop_video_streaming(
×
545
    CameraServer::StopVideoStreamingHandle handle)
546
{
NEW
547
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
548
    return _stop_video_streaming_callbacks.unsubscribe(handle);
×
UNCOV
549
}
×
550

551
CameraServer::Result CameraServerImpl::respond_stop_video_streaming(
×
552
    CameraServer::CameraFeedback stop_video_streaming_feedback)
553
{
NEW
554
    std::lock_guard<std::mutex> lg{_mutex};
×
555

556
    switch (stop_video_streaming_feedback) {
×
557
        default:
×
558
            // Fallthrough
559
        case CameraServer::CameraFeedback::Unknown:
560
            return CameraServer::Result::Error;
×
561
        case CameraServer::CameraFeedback::Ok: {
×
562
            auto command_ack = _server_component_impl->make_command_ack_message(
×
563
                _last_stop_video_streaming_command, MAV_RESULT_ACCEPTED);
×
564
            _server_component_impl->send_command_ack(command_ack);
×
565
            return CameraServer::Result::Success;
×
566
        }
567
        case CameraServer::CameraFeedback::Busy: {
×
568
            auto command_ack = _server_component_impl->make_command_ack_message(
×
569
                _last_stop_video_streaming_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
570
            _server_component_impl->send_command_ack(command_ack);
×
571
            return CameraServer::Result::Success;
×
572
        }
573
        case CameraServer::CameraFeedback::Failed: {
×
574
            auto command_ack = _server_component_impl->make_command_ack_message(
×
575
                _last_stop_video_streaming_command, MAV_RESULT_FAILED);
×
576
            _server_component_impl->send_command_ack(command_ack);
×
577
            return CameraServer::Result::Success;
×
578
        }
579
    }
UNCOV
580
}
×
581

582
CameraServer::SetModeHandle
583
CameraServerImpl::subscribe_set_mode(const CameraServer::SetModeCallback& callback)
2✔
584
{
585
    std::lock_guard<std::mutex> lg{_mutex};
2✔
586
    return _set_mode_callbacks.subscribe(callback);
2✔
587
}
2✔
588

589
void CameraServerImpl::unsubscribe_set_mode(CameraServer::SetModeHandle handle)
1✔
590
{
591
    std::lock_guard<std::mutex> lg{_mutex};
1✔
592
    _set_mode_callbacks.unsubscribe(handle);
1✔
593
}
1✔
594

595
CameraServer::Result
596
CameraServerImpl::respond_set_mode(CameraServer::CameraFeedback set_mode_feedback)
2✔
597
{
598
    std::lock_guard<std::mutex> lg{_mutex};
2✔
599

600
    switch (set_mode_feedback) {
2✔
601
        default:
×
602
            // Fallthrough
603
        case CameraServer::CameraFeedback::Unknown:
604
            return CameraServer::Result::Error;
×
605
        case CameraServer::CameraFeedback::Ok: {
2✔
606
            auto command_ack = _server_component_impl->make_command_ack_message(
2✔
607
                _last_set_mode_command, MAV_RESULT_ACCEPTED);
2✔
608
            _server_component_impl->send_command_ack(command_ack);
2✔
609
            return CameraServer::Result::Success;
2✔
610
        }
611
        case CameraServer::CameraFeedback::Busy: {
×
612
            auto command_ack = _server_component_impl->make_command_ack_message(
×
613
                _last_set_mode_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
614
            _server_component_impl->send_command_ack(command_ack);
×
615
            return CameraServer::Result::Success;
×
616
        }
617
        case CameraServer::CameraFeedback::Failed: {
×
618
            auto command_ack = _server_component_impl->make_command_ack_message(
×
619
                _last_set_mode_command, MAV_RESULT_FAILED);
×
620
            _server_component_impl->send_command_ack(command_ack);
×
621
            return CameraServer::Result::Success;
×
622
        }
623
    }
624
}
2✔
625

626
CameraServer::StorageInformationHandle CameraServerImpl::subscribe_storage_information(
1✔
627
    const CameraServer::StorageInformationCallback& callback)
628
{
629
    std::lock_guard<std::mutex> lg{_mutex};
1✔
630
    return _storage_information_callbacks.subscribe(callback);
1✔
631
}
1✔
632

633
void CameraServerImpl::unsubscribe_storage_information(
×
634
    CameraServer::StorageInformationHandle handle)
635
{
NEW
636
    std::lock_guard<std::mutex> lg{_mutex};
×
637
    _storage_information_callbacks.unsubscribe(handle);
×
638
}
×
639

640
CameraServer::Result CameraServerImpl::respond_storage_information(
1✔
641
    CameraServer::CameraFeedback storage_information_feedback,
642
    CameraServer::StorageInformation storage_information)
643
{
644
    std::lock_guard<std::mutex> lg{_mutex};
1✔
645

646
    switch (storage_information_feedback) {
1✔
647
        default:
×
648
            // Fallthrough
649
        case CameraServer::CameraFeedback::Unknown:
650
            return CameraServer::Result::Error;
×
651
        case CameraServer::CameraFeedback::Ok: {
1✔
652
            auto command_ack = _server_component_impl->make_command_ack_message(
1✔
653
                _last_storage_information_command, MAV_RESULT_ACCEPTED);
1✔
654
            _server_component_impl->send_command_ack(command_ack);
1✔
655
            // break and send storage information
656
            break;
1✔
657
        }
658
        case CameraServer::CameraFeedback::Busy: {
×
659
            auto command_ack = _server_component_impl->make_command_ack_message(
×
660
                _last_storage_information_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
661
            _server_component_impl->send_command_ack(command_ack);
×
662
            return CameraServer::Result::Success;
×
663
        }
664
        case CameraServer::CameraFeedback::Failed: {
×
665
            auto command_ack = _server_component_impl->make_command_ack_message(
×
666
                _last_storage_information_command, MAV_RESULT_FAILED);
×
667
            _server_component_impl->send_command_ack(command_ack);
×
668
            return CameraServer::Result::Success;
×
669
        }
670
    }
671

672
    const uint8_t storage_count = 1;
1✔
673

674
    const float total_capacity = storage_information.total_storage_mib;
1✔
675
    const float used_capacity = storage_information.used_storage_mib;
1✔
676
    const float available_capacity = storage_information.available_storage_mib;
1✔
677
    const float read_speed = storage_information.read_speed_mib_s;
1✔
678
    const float write_speed = storage_information.write_speed_mib_s;
1✔
679

680
    auto status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
1✔
681
    switch (storage_information.storage_status) {
1✔
682
        case CameraServer::StorageInformation::StorageStatus::NotAvailable:
×
683
            status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
684
            break;
×
685
        case CameraServer::StorageInformation::StorageStatus::Unformatted:
×
686
            status = STORAGE_STATUS::STORAGE_STATUS_UNFORMATTED;
×
687
            break;
×
688
        case CameraServer::StorageInformation::StorageStatus::Formatted:
1✔
689
            status = STORAGE_STATUS::STORAGE_STATUS_READY;
1✔
690
            break;
1✔
691
        case CameraServer::StorageInformation::StorageStatus::NotSupported:
×
692
            status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
693
            break;
×
694
    }
695

696
    auto type = STORAGE_TYPE::STORAGE_TYPE_UNKNOWN;
1✔
697
    switch (storage_information.storage_type) {
1✔
698
        case CameraServer::StorageInformation::StorageType::UsbStick:
×
699
            type = STORAGE_TYPE::STORAGE_TYPE_USB_STICK;
×
700
            break;
×
701
        case CameraServer::StorageInformation::StorageType::Sd:
×
702
            type = STORAGE_TYPE::STORAGE_TYPE_SD;
×
703
            break;
×
704
        case CameraServer::StorageInformation::StorageType::Microsd:
×
705
            type = STORAGE_TYPE::STORAGE_TYPE_MICROSD;
×
706
            break;
×
707
        case CameraServer::StorageInformation::StorageType::Hd:
×
708
            type = STORAGE_TYPE::STORAGE_TYPE_HD;
×
709
            break;
×
710
        case CameraServer::StorageInformation::StorageType::Other:
×
711
            type = STORAGE_TYPE::STORAGE_TYPE_OTHER;
×
712
            break;
×
713
        default:
1✔
714
            break;
1✔
715
    }
716

717
    std::string name("");
2✔
718
    // This needs to be long enough, otherwise the memcpy in mavlink overflows.
719
    name.resize(32);
1✔
720
    const uint8_t storage_usage = 0;
1✔
721

722
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
1✔
723
        mavlink_message_t message{};
1✔
724
        mavlink_msg_storage_information_pack_chan(
2✔
725
            mavlink_address.system_id,
1✔
726
            mavlink_address.component_id,
1✔
727
            channel,
728
            &message,
729
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
1✔
730
            _last_storage_id,
1✔
731
            storage_count,
732
            status,
1✔
733
            total_capacity,
1✔
734
            used_capacity,
1✔
735
            available_capacity,
1✔
736
            read_speed,
1✔
737
            write_speed,
1✔
738
            type,
1✔
739
            name.data(),
1✔
740
            storage_usage);
741
        return message;
1✔
742
    });
743

744
    return CameraServer::Result::Success;
1✔
745
}
1✔
746

747
CameraServer::CaptureStatusHandle
748
CameraServerImpl::subscribe_capture_status(const CameraServer::CaptureStatusCallback& callback)
×
749
{
NEW
750
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
751
    return _capture_status_callbacks.subscribe(callback);
×
UNCOV
752
}
×
753

754
void CameraServerImpl::unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle)
×
755
{
NEW
756
    std::lock_guard<std::mutex> lg{_mutex};
×
757
    _capture_status_callbacks.unsubscribe(handle);
×
758
}
×
759

760
CameraServer::Result CameraServerImpl::respond_capture_status(
×
761
    CameraServer::CameraFeedback capture_status_feedback,
762
    CameraServer::CaptureStatus capture_status)
763
{
NEW
764
    std::lock_guard<std::mutex> lg{_mutex};
×
765

766
    switch (capture_status_feedback) {
×
767
        default:
×
768
            // Fallthrough
769
        case CameraServer::CameraFeedback::Unknown:
770
            return CameraServer::Result::Error;
×
771
        case CameraServer::CameraFeedback::Ok: {
×
772
            auto command_ack = _server_component_impl->make_command_ack_message(
×
773
                _last_capture_status_command, MAV_RESULT_ACCEPTED);
×
774
            _server_component_impl->send_command_ack(command_ack);
×
775
            // break and send capture status
776
            break;
×
777
        }
778
        case CameraServer::CameraFeedback::Busy: {
×
779
            auto command_ack = _server_component_impl->make_command_ack_message(
×
780
                _last_capture_status_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
781
            _server_component_impl->send_command_ack(command_ack);
×
782
            return CameraServer::Result::Success;
×
783
        }
784
        case CameraServer::CameraFeedback::Failed: {
×
785
            auto command_ack = _server_component_impl->make_command_ack_message(
×
786
                _last_capture_status_command, MAV_RESULT_FAILED);
×
787
            _server_component_impl->send_command_ack(command_ack);
×
788
            return CameraServer::Result::Success;
×
789
        }
790
    }
791

792
    _capture_status = capture_status;
×
793

794
    send_capture_status();
×
795

796
    return CameraServer::Result::Success;
×
UNCOV
797
}
×
798

799
CameraServer::FormatStorageHandle
800
CameraServerImpl::subscribe_format_storage(const CameraServer::FormatStorageCallback& callback)
1✔
801
{
802
    std::lock_guard<std::mutex> lg{_mutex};
1✔
803
    return _format_storage_callbacks.subscribe(callback);
1✔
804
}
1✔
805
void CameraServerImpl::unsubscribe_format_storage(CameraServer::FormatStorageHandle handle)
1✔
806
{
807
    std::lock_guard<std::mutex> lg{_mutex};
1✔
808
    _format_storage_callbacks.unsubscribe(handle);
1✔
809
}
1✔
810

811
CameraServer::Result
812
CameraServerImpl::respond_format_storage(CameraServer::CameraFeedback format_storage_feedback)
1✔
813
{
814
    std::lock_guard<std::mutex> lg{_mutex};
1✔
815

816
    switch (format_storage_feedback) {
1✔
817
        default:
×
818
            // Fallthrough
819
        case CameraServer::CameraFeedback::Unknown:
820
            return CameraServer::Result::Error;
×
821
        case CameraServer::CameraFeedback::Ok: {
1✔
822
            auto command_ack = _server_component_impl->make_command_ack_message(
1✔
823
                _last_format_storage_command, MAV_RESULT_ACCEPTED);
1✔
824
            _server_component_impl->send_command_ack(command_ack);
1✔
825
            return CameraServer::Result::Success;
1✔
826
        }
827
        case CameraServer::CameraFeedback::Busy: {
×
828
            auto command_ack = _server_component_impl->make_command_ack_message(
×
829
                _last_format_storage_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
830
            _server_component_impl->send_command_ack(command_ack);
×
831
            return CameraServer::Result::Success;
×
832
        }
833
        case CameraServer::CameraFeedback::Failed: {
×
834
            auto command_ack = _server_component_impl->make_command_ack_message(
×
835
                _last_format_storage_command, MAV_RESULT_FAILED);
×
836
            _server_component_impl->send_command_ack(command_ack);
×
837
            return CameraServer::Result::Success;
×
838
        }
839
    }
840
}
1✔
841

842
CameraServer::ResetSettingsHandle
843
CameraServerImpl::subscribe_reset_settings(const CameraServer::ResetSettingsCallback& callback)
1✔
844
{
845
    std::lock_guard<std::mutex> lg{_mutex};
1✔
846
    return _reset_settings_callbacks.subscribe(callback);
1✔
847
}
1✔
848

849
void CameraServerImpl::unsubscribe_reset_settings(CameraServer::ResetSettingsHandle handle)
×
850
{
NEW
851
    std::lock_guard<std::mutex> lg{_mutex};
×
852
    _reset_settings_callbacks.unsubscribe(handle);
×
853
}
×
854

855
CameraServer::Result
856
CameraServerImpl::respond_reset_settings(CameraServer::CameraFeedback reset_settings_feedback)
1✔
857
{
858
    std::lock_guard<std::mutex> lg{_mutex};
1✔
859

860
    switch (reset_settings_feedback) {
1✔
861
        default:
×
862
            // Fallthrough
863
        case CameraServer::CameraFeedback::Unknown:
864
            return CameraServer::Result::Error;
×
865
        case CameraServer::CameraFeedback::Ok: {
1✔
866
            auto command_ack = _server_component_impl->make_command_ack_message(
1✔
867
                _last_reset_settings_command, MAV_RESULT_ACCEPTED);
1✔
868
            _server_component_impl->send_command_ack(command_ack);
1✔
869
            return CameraServer::Result::Success;
1✔
870
        }
871
        case CameraServer::CameraFeedback::Busy: {
×
872
            auto command_ack = _server_component_impl->make_command_ack_message(
×
873
                _last_reset_settings_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
874
            _server_component_impl->send_command_ack(command_ack);
×
875
            return CameraServer::Result::Success;
×
876
        }
877
        case CameraServer::CameraFeedback::Failed: {
×
878
            auto command_ack = _server_component_impl->make_command_ack_message(
×
879
                _last_reset_settings_command, MAV_RESULT_FAILED);
×
880
            _server_component_impl->send_command_ack(command_ack);
×
881
            return CameraServer::Result::Success;
×
882
        }
883
    }
884
}
1✔
885

886
CameraServer::TrackingPointCommandHandle CameraServerImpl::subscribe_tracking_point_command(
×
887
    const CameraServer::TrackingPointCommandCallback& callback)
888
{
NEW
889
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
890
    return _tracking_point_callbacks.subscribe(callback);
×
UNCOV
891
}
×
892

893
void CameraServerImpl::unsubscribe_tracking_point_command(
×
894
    CameraServer::TrackingPointCommandHandle handle)
895
{
NEW
896
    std::lock_guard<std::mutex> lg{_mutex};
×
897
    _tracking_point_callbacks.unsubscribe(handle);
×
898
}
×
899

900
CameraServer::Result CameraServerImpl::respond_tracking_point_command(
×
901
    CameraServer::CameraFeedback tracking_point_feedback)
902
{
NEW
903
    std::lock_guard<std::mutex> lg{_mutex};
×
904

905
    switch (tracking_point_feedback) {
×
906
        default:
×
907
            // Fallthrough
908
        case CameraServer::CameraFeedback::Unknown:
909
            return CameraServer::Result::Error;
×
910
        case CameraServer::CameraFeedback::Ok: {
×
911
            auto command_ack = _server_component_impl->make_command_ack_message(
×
912
                _last_track_point_command, MAV_RESULT_ACCEPTED);
×
913
            _server_component_impl->send_command_ack(command_ack);
×
914
            break;
×
915
        }
916
        case CameraServer::CameraFeedback::Busy: {
×
917
            auto command_ack = _server_component_impl->make_command_ack_message(
×
918
                _last_track_point_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
919
            _server_component_impl->send_command_ack(command_ack);
×
920
            return CameraServer::Result::Success;
×
921
        }
922
        case CameraServer::CameraFeedback::Failed: {
×
923
            auto command_ack = _server_component_impl->make_command_ack_message(
×
924
                _last_track_point_command, MAV_RESULT_FAILED);
×
925
            _server_component_impl->send_command_ack(command_ack);
×
926
            return CameraServer::Result::Success;
×
927
        }
928
    }
929
    return CameraServer::Result::Success;
×
UNCOV
930
}
×
931

932
CameraServer::TrackingRectangleCommandHandle CameraServerImpl::subscribe_tracking_rectangle_command(
×
933
    const CameraServer::TrackingRectangleCommandCallback& callback)
934
{
NEW
935
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
936
    return _tracking_rectangle_callbacks.subscribe(callback);
×
UNCOV
937
}
×
938

939
void CameraServerImpl::unsubscribe_tracking_rectangle_command(
×
940
    CameraServer::TrackingRectangleCommandHandle handle)
941
{
NEW
942
    std::lock_guard<std::mutex> lg{_mutex};
×
943
    _tracking_rectangle_callbacks.unsubscribe(handle);
×
944
}
×
945

946
CameraServer::Result CameraServerImpl::respond_tracking_rectangle_command(
×
947
    CameraServer::CameraFeedback tracking_rectangle_feedback)
948
{
NEW
949
    std::lock_guard<std::mutex> lg{_mutex};
×
950

951
    switch (tracking_rectangle_feedback) {
×
952
        default:
×
953
            // Fallthrough
954
        case CameraServer::CameraFeedback::Unknown:
955
            return CameraServer::Result::Error;
×
956
        case CameraServer::CameraFeedback::Ok: {
×
957
            auto command_ack = _server_component_impl->make_command_ack_message(
×
958
                _last_track_rectangle_command, MAV_RESULT_ACCEPTED);
×
959
            _server_component_impl->send_command_ack(command_ack);
×
960
            break;
×
961
        }
962
        case CameraServer::CameraFeedback::Busy: {
×
963
            auto command_ack = _server_component_impl->make_command_ack_message(
×
964
                _last_track_rectangle_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
965
            _server_component_impl->send_command_ack(command_ack);
×
966
            return CameraServer::Result::Success;
×
967
        }
968
        case CameraServer::CameraFeedback::Failed: {
×
969
            auto command_ack = _server_component_impl->make_command_ack_message(
×
970
                _last_track_rectangle_command, MAV_RESULT_FAILED);
×
971
            _server_component_impl->send_command_ack(command_ack);
×
972
            return CameraServer::Result::Success;
×
973
        }
974
    }
975
    return CameraServer::Result::Success;
×
UNCOV
976
}
×
977

978
CameraServer::TrackingOffCommandHandle CameraServerImpl::subscribe_tracking_off_command(
×
979
    const CameraServer::TrackingOffCommandCallback& callback)
980
{
NEW
981
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
982
    return _tracking_off_callbacks.subscribe(callback);
×
UNCOV
983
}
×
984

985
void CameraServerImpl::unsubscribe_tracking_off_command(
×
986
    CameraServer::TrackingOffCommandHandle handle)
987
{
NEW
988
    std::lock_guard<std::mutex> lg{_mutex};
×
989
    _tracking_off_callbacks.unsubscribe(handle);
×
990
}
×
991

992
CameraServer::Result
993
CameraServerImpl::respond_tracking_off_command(CameraServer::CameraFeedback tracking_off_feedback)
×
994
{
NEW
995
    std::lock_guard<std::mutex> lg{_mutex};
×
996

997
    switch (tracking_off_feedback) {
×
998
        default:
×
999
            // Fallthrough
1000
        case CameraServer::CameraFeedback::Unknown:
1001
            return CameraServer::Result::Error;
×
1002
        case CameraServer::CameraFeedback::Ok: {
×
1003
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1004
                _last_tracking_off_command, MAV_RESULT_ACCEPTED);
×
1005
            _server_component_impl->send_command_ack(command_ack);
×
1006
            break;
×
1007
        }
1008
        case CameraServer::CameraFeedback::Busy: {
×
1009
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1010
                _last_tracking_off_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1011
            _server_component_impl->send_command_ack(command_ack);
×
1012
            return CameraServer::Result::Success;
×
1013
        }
1014
        case CameraServer::CameraFeedback::Failed: {
×
1015
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1016
                _last_tracking_off_command, MAV_RESULT_FAILED);
×
1017
            _server_component_impl->send_command_ack(command_ack);
×
1018
            return CameraServer::Result::Success;
×
1019
        }
1020
    }
1021
    return CameraServer::Result::Success;
×
UNCOV
1022
}
×
1023

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

1029
    _last_interval_index = index;
1✔
1030

1031
    _image_capture_timer_cookie = _server_component_impl->add_call_every(
1✔
1032
        [this, remaining]() {
15✔
1033
            LogDebug() << "capture image timer triggered";
3✔
1034

1035
            if (!_take_photo_callbacks.empty()) {
3✔
1036
                _take_photo_callbacks.queue(_last_interval_index++, [this](const auto& func) {
3✔
1037
                    _server_component_impl->call_user_callback(func);
3✔
1038
                });
3✔
1039
                (*remaining)--;
3✔
1040
            }
1041

1042
            if (*remaining == 0) {
3✔
1043
                stop_image_capture_interval();
×
1044
            }
1045
        },
3✔
1046
        interval_s);
1047

1048
    _is_image_capture_interval_set = true;
1✔
1049
    _image_capture_timer_interval_s = interval_s;
1✔
1050
}
1✔
1051

1052
void CameraServerImpl::stop_image_capture_interval()
12✔
1053
{
1054
    _server_component_impl->remove_call_every(_image_capture_timer_cookie);
12✔
1055

1056
    std::lock_guard<std::mutex> lg{_mutex};
12✔
1057
    _is_image_capture_interval_set = false;
12✔
1058
    _image_capture_timer_interval_s = 0;
12✔
1059
}
12✔
1060

1061
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_information_request(
×
1062
    const MavlinkCommandReceiver::CommandLong& command)
1063
{
1064
    LogDebug() << "Camera info request";
×
1065

1066
    if (static_cast<int>(command.params.param1) == 0) {
×
1067
        return _server_component_impl->make_command_ack_message(
×
1068
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1069
    }
1070

1071
    return send_camera_information(command);
×
1072
}
1073

1074
std::optional<mavlink_command_ack_t>
1075
CameraServerImpl::process_request_message(const MavlinkCommandReceiver::CommandLong& command)
40✔
1076
{
1077
    switch (static_cast<int>(command.params.param1)) {
40✔
1078
        case MAVLINK_MSG_ID_CAMERA_INFORMATION:
9✔
1079
            return send_camera_information(command);
9✔
1080

1081
        case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS:
5✔
1082
            send_capture_status();
5✔
1083
            return _server_component_impl->make_command_ack_message(
10✔
1084
                command, MAV_RESULT::MAV_RESULT_ACCEPTED);
10✔
1085

1086
        default:
26✔
1087
            LogWarn() << "Got unknown request message!";
26✔
1088
            return _server_component_impl->make_command_ack_message(
52✔
1089
                command, MAV_RESULT::MAV_RESULT_DENIED);
52✔
1090
    }
1091
}
1092

1093
std::optional<mavlink_command_ack_t>
1094
CameraServerImpl::send_camera_information(const MavlinkCommandReceiver::CommandLong& command)
9✔
1095
{
1096
    std::lock_guard<std::mutex> lg{_mutex};
9✔
1097

1098
    if (!_is_information_set) {
9✔
1099
        return _server_component_impl->make_command_ack_message(
×
1100
            command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED);
×
1101
    }
1102

1103
    // ack needs to be sent before camera information message
1104
    auto command_ack =
9✔
1105
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
9✔
1106
    _server_component_impl->send_command_ack(command_ack);
9✔
1107

1108
    // It is safe to ignore the return value of parse_version_string() here
1109
    // since the string was already validated in set_information().
1110
    uint32_t firmware_version;
9✔
1111
    parse_version_string(_information.firmware_version, firmware_version);
9✔
1112

1113
    // capability flags are determined by subscriptions
1114
    uint32_t capability_flags{};
9✔
1115

1116
    if (!_take_photo_callbacks.empty()) {
9✔
1117
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE;
2✔
1118
    }
1119

1120
    if (!_start_video_callbacks.empty()) {
9✔
1121
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
×
1122
    }
1123

1124
    if (!_set_mode_callbacks.empty()) {
9✔
1125
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES;
2✔
1126
    }
1127

1128
    if (_information.image_in_video_mode_supported) {
9✔
1129
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE;
×
1130
    }
1131

1132
    if (_information.video_in_image_mode_supported) {
9✔
1133
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE;
×
1134
    }
1135

1136
    if (_is_video_streaming_set) {
9✔
1137
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM;
1✔
1138
    }
1139

1140
    if (!_tracking_point_callbacks.empty()) {
9✔
1141
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT;
×
1142
    }
1143

1144
    if (!_tracking_rectangle_callbacks.empty()) {
9✔
1145
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE;
×
1146
    }
1147

1148
    if (!_zoom_range_callbacks.empty() || !_zoom_in_start_callbacks.empty() ||
18✔
1149
        !_zoom_out_start_callbacks.empty()) {
9✔
1150
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM;
×
1151
    }
1152

1153
    _information.vendor_name.resize(sizeof(mavlink_camera_information_t::vendor_name));
9✔
1154
    _information.model_name.resize(sizeof(mavlink_camera_information_t::model_name));
9✔
1155
    _information.definition_file_uri.resize(
9✔
1156
        sizeof(mavlink_camera_information_t::cam_definition_uri));
1157

1158
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
9✔
1159
        mavlink_message_t message{};
9✔
1160
        mavlink_msg_camera_information_pack_chan(
27✔
1161
            mavlink_address.system_id,
9✔
1162
            mavlink_address.component_id,
9✔
1163
            channel,
1164
            &message,
1165
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
18✔
1166
            reinterpret_cast<const uint8_t*>(_information.vendor_name.c_str()),
9✔
1167
            reinterpret_cast<const uint8_t*>(_information.model_name.c_str()),
9✔
1168
            firmware_version,
9✔
1169
            _information.focal_length_mm,
1170
            _information.horizontal_sensor_size_mm,
1171
            _information.vertical_sensor_size_mm,
1172
            _information.horizontal_resolution_px,
9✔
1173
            _information.vertical_resolution_px,
9✔
1174
            _information.lens_id,
9✔
1175
            capability_flags,
9✔
1176
            _information.definition_file_version,
9✔
1177
            _information.definition_file_uri.c_str(),
1178
            0,
1179
            0);
1180
        return message;
9✔
1181
    });
1182

1183
    return std::nullopt;
9✔
1184
}
9✔
1185

1186
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_settings_request(
5✔
1187
    const MavlinkCommandReceiver::CommandLong& command)
1188
{
1189
    auto settings = static_cast<bool>(command.params.param1);
5✔
1190

1191
    if (!settings) {
5✔
1192
        return _server_component_impl->make_command_ack_message(
×
1193
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1194
    }
1195

1196
    // ack needs to be sent before camera information message
1197
    auto command_ack =
5✔
1198
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
5✔
1199
    _server_component_impl->send_command_ack(command_ack);
5✔
1200
    LogDebug() << "sent settings ack";
5✔
1201

1202
    // unsupported
1203
    const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE;
5✔
1204
    const float zoom_level = 0;
5✔
1205
    const float focus_level = 0;
5✔
1206

1207
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
5✔
1208
        mavlink_message_t message{};
5✔
1209
        mavlink_msg_camera_settings_pack_chan(
10✔
1210
            mavlink_address.system_id,
5✔
1211
            mavlink_address.component_id,
5✔
1212
            channel,
1213
            &message,
1214
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
5✔
1215
            mode_id,
1216
            zoom_level,
5✔
1217
            focus_level,
5✔
1218
            0);
1219
        return message;
5✔
1220
    });
1221
    LogDebug() << "sent settings msg";
5✔
1222

1223
    // ack was already sent
1224
    return std::nullopt;
5✔
1225
}
1226

1227
std::optional<mavlink_command_ack_t> CameraServerImpl::process_storage_information_request(
9✔
1228
    const MavlinkCommandReceiver::CommandLong& command)
1229
{
1230
    auto storage_id = static_cast<uint8_t>(command.params.param1);
9✔
1231
    auto information = static_cast<bool>(command.params.param2);
9✔
1232

1233
    if (!information) {
9✔
1234
        return _server_component_impl->make_command_ack_message(
×
1235
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1236
    }
1237

1238
    std::lock_guard<std::mutex> lg{_mutex};
9✔
1239

1240
    if (_storage_information_callbacks.empty()) {
9✔
1241
        LogDebug()
16✔
1242
            << "Get storage information requested with no set storage information subscriber";
16✔
1243
        return _server_component_impl->make_command_ack_message(
16✔
1244
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
16✔
1245
    }
1246

1247
    // TODO may need support multi storage id
1248
    _last_storage_id = storage_id;
1✔
1249

1250
    _last_storage_information_command = command;
1✔
1251

1252
    _storage_information_callbacks.queue(
1✔
1253
        storage_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
1✔
1254

1255
    // ack will be sent later in respond_storage_information
1256
    return std::nullopt;
1✔
1257
}
9✔
1258

1259
std::optional<mavlink_command_ack_t>
1260
CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLong& command)
1✔
1261
{
1262
    auto storage_id = static_cast<uint8_t>(command.params.param1);
1✔
1263
    auto format = static_cast<bool>(command.params.param2);
1✔
1264
    auto reset_image_log = static_cast<bool>(command.params.param3);
1✔
1265

1266
    UNUSED(format);
1✔
1267
    UNUSED(reset_image_log);
1✔
1268

1269
    std::lock_guard<std::mutex> lg{_mutex};
1✔
1270

1271
    if (_format_storage_callbacks.empty()) {
1✔
1272
        LogDebug() << "process storage format requested with no storage format subscriber";
×
1273
        return _server_component_impl->make_command_ack_message(
×
1274
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1275
    }
1276

1277
    _last_format_storage_command = command;
1✔
1278

1279
    _format_storage_callbacks.queue(
1✔
1280
        storage_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
1✔
1281

1282
    return std::nullopt;
1✔
1283
}
1✔
1284

1285
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_capture_status_request(
×
1286
    const MavlinkCommandReceiver::CommandLong& command)
1287
{
1288
    auto capture_status = static_cast<bool>(command.params.param1);
×
1289

1290
    if (!capture_status) {
×
1291
        return _server_component_impl->make_command_ack_message(
×
1292
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1293
    }
1294

NEW
1295
    std::lock_guard<std::mutex> lg{_mutex};
×
1296
    if (_capture_status_callbacks.empty()) {
×
1297
        LogDebug() << "process camera capture status requested with no capture status subscriber";
×
1298
        return _server_component_impl->make_command_ack_message(
×
1299
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1300
    }
1301

1302
    _last_capture_status_command = command;
×
1303

1304
    // may not need param for now ,just use zero
NEW
1305
    _capture_status_callbacks.queue(
×
NEW
1306
        0, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1307

1308
    // ack was already sent
1309
    return std::nullopt;
×
UNCOV
1310
}
×
1311

1312
void CameraServerImpl::send_capture_status()
5✔
1313
{
1314
    std::lock_guard<std::mutex> lg{_mutex};
5✔
1315

1316
    uint8_t image_status{};
5✔
1317
    if (_capture_status.image_status ==
5✔
1318
            CameraServer::CaptureStatus::ImageStatus::CaptureInProgress ||
5✔
1319
        _capture_status.image_status ==
5✔
1320
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress) {
1321
        image_status |= StatusFlags::IN_PROGRESS;
×
1322
    }
1323

1324
    if (_capture_status.image_status == CameraServer::CaptureStatus::ImageStatus::IntervalIdle ||
5✔
1325
        _capture_status.image_status ==
5✔
1326
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress ||
5✔
1327
        _is_image_capture_interval_set) {
5✔
1328
        image_status |= StatusFlags::INTERVAL_SET;
×
1329
    }
1330

1331
    uint8_t video_status = 0;
5✔
1332
    if (_capture_status.video_status == CameraServer::CaptureStatus::VideoStatus::Idle) {
5✔
1333
        video_status = 0;
5✔
1334
    } else if (
×
1335
        _capture_status.video_status ==
×
1336
        CameraServer::CaptureStatus::VideoStatus::CaptureInProgress) {
1337
        video_status = 1;
×
1338
    }
1339

1340
    const uint32_t recording_time_ms =
5✔
1341
        static_cast<uint32_t>(static_cast<double>(_capture_status.recording_time_s) * 1e3);
5✔
1342
    const float available_capacity = _capture_status.available_capacity_mib;
5✔
1343

1344
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
5✔
1345
        mavlink_message_t message{};
5✔
1346
        mavlink_msg_camera_capture_status_pack_chan(
10✔
1347
            mavlink_address.system_id,
5✔
1348
            mavlink_address.component_id,
5✔
1349
            channel,
1350
            &message,
1351
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
5✔
1352
            image_status,
5✔
1353
            video_status,
5✔
1354
            _image_capture_timer_interval_s,
1355
            recording_time_ms,
5✔
1356
            available_capacity,
5✔
1357
            _image_capture_count,
1358
            0);
1359
        return message;
5✔
1360
    });
1361
}
5✔
1362

1363
std::optional<mavlink_command_ack_t>
1364
CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::CommandLong& command)
1✔
1365
{
1366
    auto reset = static_cast<bool>(command.params.param1);
1✔
1367

1368
    UNUSED(reset);
1✔
1369

1370
    std::lock_guard<std::mutex> lg{_mutex};
1✔
1371

1372
    if (_reset_settings_callbacks.empty()) {
1✔
1373
        LogDebug() << "reset camera settings requested with no camera settings subscriber";
×
1374
        return _server_component_impl->make_command_ack_message(
×
1375
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1376
    }
1377

1378
    _last_reset_settings_command = command;
1✔
1379
    _reset_settings_callbacks.queue(
1✔
1380
        0, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
1✔
1381

1382
    return std::nullopt;
1✔
1383
}
1✔
1384

1385
std::optional<mavlink_command_ack_t>
1386
CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandLong& command)
2✔
1387
{
1388
    auto camera_mode = static_cast<CAMERA_MODE>(command.params.param2);
2✔
1389

1390
    std::lock_guard<std::mutex> lg{_mutex};
2✔
1391

1392
    if (_set_mode_callbacks.empty()) {
2✔
1393
        LogDebug() << "Set mode requested with no set mode subscriber";
×
1394
        return _server_component_impl->make_command_ack_message(
×
1395
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1396
    }
1397

1398
    // convert camera mode enum type
1399
    CameraServer::Mode convert_camera_mode = CameraServer::Mode::Unknown;
2✔
1400
    if (camera_mode == CAMERA_MODE_IMAGE) {
2✔
1401
        convert_camera_mode = CameraServer::Mode::Photo;
1✔
1402
    } else if (camera_mode == CAMERA_MODE_VIDEO) {
1✔
1403
        convert_camera_mode = CameraServer::Mode::Video;
1✔
1404
    }
1405

1406
    if (convert_camera_mode == CameraServer::Mode::Unknown) {
2✔
1407
        return _server_component_impl->make_command_ack_message(
×
1408
            command, MAV_RESULT::MAV_RESULT_DENIED);
×
1409
    }
1410

1411
    _last_set_mode_command = command;
2✔
1412

1413
    _set_mode_callbacks.queue(convert_camera_mode, [this](const auto& func) {
2✔
1414
        _server_component_impl->call_user_callback(func);
2✔
1415
    });
2✔
1416

1417
    return std::nullopt;
2✔
1418
}
2✔
1419

1420
std::optional<mavlink_command_ack_t>
1421
CameraServerImpl::process_set_camera_zoom(const MavlinkCommandReceiver::CommandLong& command)
×
1422
{
1423
    auto zoom_type = static_cast<CAMERA_ZOOM_TYPE>(command.params.param1);
×
1424
    auto zoom_value = command.params.param2;
×
1425

NEW
1426
    std::lock_guard<std::mutex> lg{_mutex};
×
1427

1428
    if (_zoom_in_start_callbacks.empty() && _zoom_out_start_callbacks.empty() &&
×
1429
        _zoom_stop_callbacks.empty() && _zoom_range_callbacks.empty()) {
×
1430
        LogWarn() << "No camera zoom is supported";
×
1431
        return _server_component_impl->make_command_ack_message(
×
1432
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1433
    }
1434

1435
    auto unsupported = [&]() {
×
1436
        LogWarn() << "unsupported set camera zoom type (" << (int)zoom_type << ") request";
×
1437
    };
×
1438

1439
    switch (zoom_type) {
×
1440
        case ZOOM_TYPE_CONTINUOUS:
×
1441
            if (zoom_value == -1.f) {
×
1442
                if (_zoom_out_start_callbacks.empty()) {
×
1443
                    unsupported();
×
1444
                    return _server_component_impl->make_command_ack_message(
×
1445
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1446
                } else {
1447
                    _last_zoom_out_start_command = command;
×
1448
                    int dummy = 0;
×
NEW
1449
                    _zoom_out_start_callbacks.queue(dummy, [this](const auto& func) {
×
NEW
1450
                        _server_component_impl->call_user_callback(func);
×
NEW
1451
                    });
×
1452
                }
1453
            } else if (zoom_value == 1.f) {
×
1454
                if (_zoom_in_start_callbacks.empty()) {
×
1455
                    unsupported();
×
1456
                    return _server_component_impl->make_command_ack_message(
×
1457
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1458
                } else {
1459
                    _last_zoom_in_start_command = command;
×
1460
                    int dummy = 0;
×
NEW
1461
                    _zoom_in_start_callbacks.queue(dummy, [this](const auto& func) {
×
NEW
1462
                        _server_component_impl->call_user_callback(func);
×
NEW
1463
                    });
×
1464
                }
1465
            } else if (zoom_value == 0.f) {
×
1466
                if (_zoom_stop_callbacks.empty()) {
×
1467
                    unsupported();
×
1468
                    return _server_component_impl->make_command_ack_message(
×
1469
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1470
                } else {
1471
                    _last_zoom_stop_command = command;
×
1472
                    int dummy = 0;
×
NEW
1473
                    _zoom_stop_callbacks.queue(dummy, [this](const auto& func) {
×
NEW
1474
                        _server_component_impl->call_user_callback(func);
×
NEW
1475
                    });
×
1476
                }
1477
            } else {
1478
                LogWarn() << "Invalid zoom value";
×
1479
                return _server_component_impl->make_command_ack_message(
×
1480
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1481
            }
1482
            break;
×
1483
        case ZOOM_TYPE_RANGE:
×
1484
            if (_zoom_range_callbacks.empty()) {
×
1485
                unsupported();
×
1486
                return _server_component_impl->make_command_ack_message(
×
1487
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1488

1489
            } else {
1490
                _last_zoom_range_command = command;
×
NEW
1491
                _zoom_range_callbacks.queue(zoom_value, [this](const auto& func) {
×
NEW
1492
                    _server_component_impl->call_user_callback(func);
×
NEW
1493
                });
×
1494
            }
1495
            break;
×
1496
        case ZOOM_TYPE_STEP:
×
1497
        // Fallthrough
1498
        case ZOOM_TYPE_FOCAL_LENGTH:
1499
        // Fallthrough
1500
        case ZOOM_TYPE_HORIZONTAL_FOV:
1501
        // Fallthrough
1502
        default:
1503
            unsupported();
×
1504
            return _server_component_impl->make_command_ack_message(
×
1505
                command, MAV_RESULT::MAV_RESULT_DENIED);
×
1506
            break;
1507
    }
1508

1509
    // For any success so far, we don't ack yet, but later when the respond function is called.
1510
    return std::nullopt;
×
UNCOV
1511
}
×
1512

1513
std::optional<mavlink_command_ack_t>
1514
CameraServerImpl::process_set_camera_focus(const MavlinkCommandReceiver::CommandLong& command)
×
1515
{
1516
    auto focus_type = static_cast<SET_FOCUS_TYPE>(command.params.param1);
×
1517
    auto focus_value = command.params.param2;
×
1518

1519
    UNUSED(focus_type);
×
1520
    UNUSED(focus_value);
×
1521

1522
    LogDebug() << "unsupported set camera focus request";
×
1523

1524
    return _server_component_impl->make_command_ack_message(
×
1525
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1526
}
1527

1528
std::optional<mavlink_command_ack_t>
1529
CameraServerImpl::process_set_storage_usage(const MavlinkCommandReceiver::CommandLong& command)
×
1530
{
1531
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
1532
    auto usage = static_cast<STORAGE_USAGE_FLAG>(command.params.param2);
×
1533

1534
    UNUSED(storage_id);
×
1535
    UNUSED(usage);
×
1536

1537
    LogDebug() << "unsupported set storage usage request";
×
1538

1539
    return _server_component_impl->make_command_ack_message(
×
1540
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1541
}
1542

1543
std::optional<mavlink_command_ack_t>
1544
CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command)
2✔
1545
{
1546
    auto interval_s = command.params.param2;
2✔
1547
    auto total_images = static_cast<int32_t>(command.params.param3);
2✔
1548
    auto seq_number = static_cast<int32_t>(command.params.param4);
2✔
1549

1550
    LogDebug() << "received image start capture request - interval: " << +interval_s
6✔
1551
               << " total: " << +total_images << " index: " << +seq_number;
6✔
1552

1553
    // TODO: validate parameters and return MAV_RESULT_DENIED not valid
1554

1555
    stop_image_capture_interval();
2✔
1556

1557
    std::lock_guard<std::mutex> lg{_mutex};
2✔
1558

1559
    if (_take_photo_callbacks.empty()) {
2✔
1560
        LogDebug() << "image capture requested with no take photo subscriber";
×
1561
        return _server_component_impl->make_command_ack_message(
×
1562
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1563
    }
1564

1565
    // single image capture
1566
    if (total_images == 1) {
2✔
1567
        // MAV_RESULT_ACCEPTED must be sent before CAMERA_IMAGE_CAPTURED
1568
        auto command_ack = _server_component_impl->make_command_ack_message(
1✔
1569
            command, MAV_RESULT::MAV_RESULT_IN_PROGRESS);
1570
        _server_component_impl->send_command_ack(command_ack);
1✔
1571

1572
        _last_take_photo_command = command;
1✔
1573

1574
        _take_photo_callbacks.queue(seq_number, [this](const auto& func) {
1✔
1575
            _server_component_impl->call_user_callback(func);
1✔
1576
        });
1✔
1577

1578
        return std::nullopt;
1✔
1579
    }
1580

1581
    start_image_capture_interval(interval_s, total_images, seq_number);
1✔
1582

1583
    return _server_component_impl->make_command_ack_message(
2✔
1584
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
2✔
1585
}
2✔
1586

1587
std::optional<mavlink_command_ack_t>
1588
CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
1✔
1589
{
1590
    LogDebug() << "received image stop capture request";
1✔
1591

1592
    // REVISIT: should we return something other that MAV_RESULT_ACCEPTED if
1593
    // there is not currently a capture interval active?
1594
    stop_image_capture_interval();
1✔
1595

1596
    return _server_component_impl->make_command_ack_message(
2✔
1597
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
2✔
1598
}
1599

1600
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_image_capture_request(
×
1601
    const MavlinkCommandReceiver::CommandLong& command)
1602
{
1603
    auto seq_number = static_cast<uint32_t>(command.params.param1);
×
1604

1605
    UNUSED(seq_number);
×
1606

1607
    LogDebug() << "unsupported image capture request";
×
1608

1609
    return _server_component_impl->make_command_ack_message(
×
1610
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1611
}
1612

1613
std::optional<mavlink_command_ack_t>
1614
CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1615
{
1616
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1617
    auto status_frequency = command.params.param2;
×
1618

1619
    UNUSED(status_frequency);
×
1620

NEW
1621
    std::lock_guard<std::mutex> lg{_mutex};
×
1622

1623
    if (_start_video_callbacks.empty()) {
×
1624
        LogDebug() << "video start capture requested with no video start capture subscriber";
×
1625
        return _server_component_impl->make_command_ack_message(
×
1626
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1627
    }
1628

1629
    _last_start_video_command = command;
×
NEW
1630
    _start_video_callbacks.queue(
×
NEW
1631
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1632

1633
    return std::nullopt;
×
UNCOV
1634
}
×
1635

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

NEW
1641
    std::lock_guard<std::mutex> lg{_mutex};
×
1642

1643
    if (_stop_video_callbacks.empty()) {
×
1644
        LogDebug() << "video stop capture requested with no video stop capture subscriber";
×
1645
        return _server_component_impl->make_command_ack_message(
×
1646
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1647
    }
1648

1649
    _last_stop_video_command = command;
×
NEW
1650
    _stop_video_callbacks.queue(
×
NEW
1651
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1652

1653
    return std::nullopt;
×
UNCOV
1654
}
×
1655

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

NEW
1661
    std::lock_guard<std::mutex> lg{_mutex};
×
1662

1663
    if (_start_video_streaming_callbacks.empty()) {
×
1664
        LogDebug() << "video start streaming requested with no video start streaming subscriber";
×
1665
        return _server_component_impl->make_command_ack_message(
×
1666
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1667
    }
1668

1669
    _last_start_video_streaming_command = command;
×
NEW
1670
    _start_video_streaming_callbacks.queue(
×
NEW
1671
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1672

1673
    return std::nullopt;
×
UNCOV
1674
}
×
1675

1676
std::optional<mavlink_command_ack_t>
1677
CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1678
{
1679
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1680

NEW
1681
    std::lock_guard<std::mutex> lg{_mutex};
×
1682

1683
    if (_stop_video_streaming_callbacks.empty()) {
×
1684
        LogDebug() << "video stop streaming requested with no video stop streaming subscriber";
×
1685
        return _server_component_impl->make_command_ack_message(
×
1686
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1687
    }
1688

1689
    _last_stop_video_streaming_command = command;
×
NEW
1690
    _stop_video_streaming_callbacks.queue(
×
NEW
1691
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1692

1693
    return std::nullopt;
×
UNCOV
1694
}
×
1695

1696
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_information_request(
1✔
1697
    const MavlinkCommandReceiver::CommandLong& command)
1698
{
1699
    auto stream_id = static_cast<uint8_t>(command.params.param1);
1✔
1700

1701
    UNUSED(stream_id);
1✔
1702

1703
    std::lock_guard<std::mutex> lg{_mutex};
1✔
1704

1705
    if (_is_video_streaming_set) {
1✔
1706
        auto command_ack = _server_component_impl->make_command_ack_message(
1✔
1707
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
1708
        _server_component_impl->send_command_ack(command_ack);
1✔
1709
        LogDebug() << "sent video streaming ack";
1✔
1710

1711
        const char name[32] = "";
1✔
1712

1713
        _video_streaming.rtsp_uri.resize(sizeof(mavlink_video_stream_information_t::uri));
1✔
1714

1715
        mavlink_message_t msg{};
1✔
1716
        mavlink_msg_video_stream_information_pack(
2✔
1717
            _server_component_impl->get_own_system_id(),
1✔
1718
            _server_component_impl->get_own_component_id(),
1✔
1719
            &msg,
1720
            0, // Stream id
1721
            0, // Count
1722
            VIDEO_STREAM_TYPE_RTSP,
1723
            VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1724
            0, // famerate
1725
            0, // resolution horizontal
1726
            0, // resolution vertical
1727
            0, // bitrate
1728
            0, // rotation
1729
            0, // horizontal field of view
1730
            name,
1731
            _video_streaming.rtsp_uri.c_str(),
1732
            0,
1733
            0);
1734

1735
        _server_component_impl->send_message(msg);
1✔
1736

1737
        // Ack already sent.
1738
        return std::nullopt;
1✔
1739

1740
    } else {
1741
        return _server_component_impl->make_command_ack_message(
×
1742
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1743
    }
1744
}
1✔
1745

1746
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_status_request(
6✔
1747
    const MavlinkCommandReceiver::CommandLong& command)
1748
{
1749
    auto stream_id = static_cast<uint8_t>(command.params.param1);
6✔
1750

1751
    UNUSED(stream_id);
6✔
1752

1753
    std::lock_guard<std::mutex> lg{_mutex};
6✔
1754

1755
    if (!_is_video_streaming_set) {
6✔
1756
        return _server_component_impl->make_command_ack_message(
4✔
1757
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
4✔
1758
    }
1759

1760
    auto command_ack =
4✔
1761
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
4✔
1762
    _server_component_impl->send_command_ack(command_ack);
4✔
1763
    LogDebug() << "sent video streaming ack";
4✔
1764

1765
    mavlink_message_t msg{};
4✔
1766
    mavlink_msg_video_stream_status_pack(
4✔
1767
        _server_component_impl->get_own_system_id(),
4✔
1768
        _server_component_impl->get_own_component_id(),
4✔
1769
        &msg,
1770
        0, // Stream id
1771
        VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1772
        0, // framerate
1773
        0, // resolution horizontal
1774
        0, // resolution vertical
1775
        0, // bitrate
1776
        0, // rotation
1777
        0, // horizontal field of view
1778
        0);
1779
    _server_component_impl->send_message(msg);
4✔
1780

1781
    // ack was already sent
1782
    return std::nullopt;
4✔
1783
}
6✔
1784

1785
CameraServer::ZoomInStartHandle
1786
CameraServerImpl::subscribe_zoom_in_start(const CameraServer::ZoomInStartCallback& callback)
×
1787
{
NEW
1788
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1789
    return _zoom_in_start_callbacks.subscribe(callback);
×
UNCOV
1790
}
×
1791

1792
void CameraServerImpl::unsubscribe_zoom_in_start(CameraServer::ZoomInStartHandle handle)
×
1793
{
NEW
1794
    std::lock_guard<std::mutex> lg{_mutex};
×
1795
    _zoom_in_start_callbacks.unsubscribe(handle);
×
1796
}
×
1797

1798
CameraServer::Result
1799
CameraServerImpl::respond_zoom_in_start(CameraServer::CameraFeedback zoom_in_start_feedback)
×
1800
{
NEW
1801
    std::lock_guard<std::mutex> lg{_mutex};
×
1802

1803
    switch (zoom_in_start_feedback) {
×
1804
        default:
×
1805
            // Fallthrough
1806
        case CameraServer::CameraFeedback::Unknown:
1807
            return CameraServer::Result::Error;
×
1808
        case CameraServer::CameraFeedback::Ok: {
×
1809
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1810
                _last_zoom_in_start_command, MAV_RESULT_ACCEPTED);
×
1811
            _server_component_impl->send_command_ack(command_ack);
×
1812
            return CameraServer::Result::Success;
×
1813
        }
1814
        case CameraServer::CameraFeedback::Busy: {
×
1815
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1816
                _last_zoom_in_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1817
            _server_component_impl->send_command_ack(command_ack);
×
1818
            return CameraServer::Result::Success;
×
1819
        }
1820
        case CameraServer::CameraFeedback::Failed: {
×
1821
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1822
                _last_zoom_in_start_command, MAV_RESULT_FAILED);
×
1823
            _server_component_impl->send_command_ack(command_ack);
×
1824
            return CameraServer::Result::Success;
×
1825
        }
1826
    }
UNCOV
1827
}
×
1828

1829
CameraServer::ZoomOutStartHandle
1830
CameraServerImpl::subscribe_zoom_out_start(const CameraServer::ZoomOutStartCallback& callback)
×
1831
{
NEW
1832
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1833
    return _zoom_out_start_callbacks.subscribe(callback);
×
UNCOV
1834
}
×
1835

1836
void CameraServerImpl::unsubscribe_zoom_out_start(CameraServer::ZoomOutStartHandle handle)
×
1837
{
NEW
1838
    std::lock_guard<std::mutex> lg{_mutex};
×
1839
    _zoom_out_start_callbacks.unsubscribe(handle);
×
1840
}
×
1841

1842
CameraServer::Result
1843
CameraServerImpl::respond_zoom_out_start(CameraServer::CameraFeedback zoom_out_start_feedback)
×
1844
{
NEW
1845
    std::lock_guard<std::mutex> lg{_mutex};
×
1846

1847
    switch (zoom_out_start_feedback) {
×
1848
        default:
×
1849
            // Fallthrough
1850
        case CameraServer::CameraFeedback::Unknown:
1851
            return CameraServer::Result::Error;
×
1852
        case CameraServer::CameraFeedback::Ok: {
×
1853
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1854
                _last_zoom_out_start_command, MAV_RESULT_ACCEPTED);
×
1855
            _server_component_impl->send_command_ack(command_ack);
×
1856
            return CameraServer::Result::Success;
×
1857
        }
1858
        case CameraServer::CameraFeedback::Busy: {
×
1859
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1860
                _last_zoom_out_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1861
            _server_component_impl->send_command_ack(command_ack);
×
1862
            return CameraServer::Result::Success;
×
1863
        }
1864
        case CameraServer::CameraFeedback::Failed: {
×
1865
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1866
                _last_zoom_out_start_command, MAV_RESULT_FAILED);
×
1867
            _server_component_impl->send_command_ack(command_ack);
×
1868
            return CameraServer::Result::Success;
×
1869
        }
1870
    }
UNCOV
1871
}
×
1872

1873
CameraServer::ZoomStopHandle
1874
CameraServerImpl::subscribe_zoom_stop(const CameraServer::ZoomStopCallback& callback)
×
1875
{
NEW
1876
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1877
    return _zoom_stop_callbacks.subscribe(callback);
×
UNCOV
1878
}
×
1879

1880
void CameraServerImpl::unsubscribe_zoom_stop(CameraServer::ZoomStopHandle handle)
×
1881
{
NEW
1882
    std::lock_guard<std::mutex> lg{_mutex};
×
1883
    _zoom_stop_callbacks.unsubscribe(handle);
×
1884
}
×
1885

1886
CameraServer::Result
1887
CameraServerImpl::respond_zoom_stop(CameraServer::CameraFeedback zoom_stop_feedback)
×
1888
{
NEW
1889
    std::lock_guard<std::mutex> lg{_mutex};
×
1890

1891
    switch (zoom_stop_feedback) {
×
1892
        default:
×
1893
            // Fallthrough
1894
        case CameraServer::CameraFeedback::Unknown:
1895
            return CameraServer::Result::Error;
×
1896
        case CameraServer::CameraFeedback::Ok: {
×
1897
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1898
                _last_zoom_stop_command, MAV_RESULT_ACCEPTED);
×
1899
            _server_component_impl->send_command_ack(command_ack);
×
1900
            return CameraServer::Result::Success;
×
1901
        }
1902
        case CameraServer::CameraFeedback::Busy: {
×
1903
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1904
                _last_zoom_stop_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1905
            _server_component_impl->send_command_ack(command_ack);
×
1906
            return CameraServer::Result::Success;
×
1907
        }
1908
        case CameraServer::CameraFeedback::Failed: {
×
1909
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1910
                _last_zoom_stop_command, MAV_RESULT_FAILED);
×
1911
            _server_component_impl->send_command_ack(command_ack);
×
1912
            return CameraServer::Result::Success;
×
1913
        }
1914
    }
UNCOV
1915
}
×
1916

1917
CameraServer::ZoomRangeHandle
1918
CameraServerImpl::subscribe_zoom_range(const CameraServer::ZoomRangeCallback& callback)
×
1919
{
NEW
1920
    std::lock_guard<std::mutex> lg{_mutex};
×
UNCOV
1921
    return _zoom_range_callbacks.subscribe(callback);
×
UNCOV
1922
}
×
1923

1924
void CameraServerImpl::unsubscribe_zoom_range(CameraServer::ZoomRangeHandle handle)
×
1925
{
NEW
1926
    std::lock_guard<std::mutex> lg{_mutex};
×
1927
    _zoom_range_callbacks.unsubscribe(handle);
×
1928
}
×
1929

1930
CameraServer::Result
1931
CameraServerImpl::respond_zoom_range(CameraServer::CameraFeedback zoom_range_feedback)
×
1932
{
NEW
1933
    std::lock_guard<std::mutex> lg{_mutex};
×
1934

1935
    switch (zoom_range_feedback) {
×
1936
        case CameraServer::CameraFeedback::Ok: {
×
1937
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1938
                _last_zoom_range_command, MAV_RESULT_ACCEPTED);
×
1939
            _server_component_impl->send_command_ack(command_ack);
×
1940
            return CameraServer::Result::Success;
×
1941
        }
1942
        case CameraServer::CameraFeedback::Busy: {
×
1943
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1944
                _last_zoom_range_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1945
            _server_component_impl->send_command_ack(command_ack);
×
1946
            return CameraServer::Result::Success;
×
1947
        }
1948
        case CameraServer::CameraFeedback::Failed: {
×
1949
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1950
                _last_zoom_range_command, MAV_RESULT_FAILED);
×
1951
            _server_component_impl->send_command_ack(command_ack);
×
1952
            return CameraServer::Result::Success;
×
1953
        }
1954
        case CameraServer::CameraFeedback::Unknown:
×
1955
            // Fallthrough
1956
        default:
1957
            return CameraServer::Result::Error;
×
1958
    }
UNCOV
1959
}
×
1960

1961
std::optional<mavlink_command_ack_t>
1962
CameraServerImpl::process_track_point_command(const MavlinkCommandReceiver::CommandLong& command)
×
1963
{
1964
    if (!is_command_sender_ok(command)) {
×
1965
        LogWarn() << "Incoming track point command is for target sysid "
×
1966
                  << int(command.target_system_id) << " instead of "
×
1967
                  << int(_server_component_impl->get_own_system_id());
×
1968
        return std::nullopt;
×
1969
    }
1970

NEW
1971
    std::lock_guard<std::mutex> lg{_mutex};
×
1972

1973
    if (_tracking_point_callbacks.empty()) {
×
1974
        LogDebug() << "Track point requested with no user callback provided";
×
1975
        return _server_component_impl->make_command_ack_message(
×
1976
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1977
    }
1978

1979
    CameraServer::TrackPoint track_point{
×
1980
        command.params.param1, command.params.param2, command.params.param3};
×
1981

1982
    _last_track_point_command = command;
×
NEW
1983
    _tracking_point_callbacks.queue(track_point, [this](const auto& func) {
×
NEW
1984
        _server_component_impl->call_user_callback(func);
×
NEW
1985
    });
×
1986
    // We don't send an ack but leave that to the user.
1987
    return std::nullopt;
×
UNCOV
1988
}
×
1989

1990
std::optional<mavlink_command_ack_t> CameraServerImpl::process_track_rectangle_command(
×
1991
    const MavlinkCommandReceiver::CommandLong& command)
1992
{
1993
    if (!is_command_sender_ok(command)) {
×
1994
        LogWarn() << "Incoming track rectangle command is for target sysid "
×
1995
                  << int(command.target_system_id) << " instead of "
×
1996
                  << int(_server_component_impl->get_own_system_id());
×
1997
        return std::nullopt;
×
1998
    }
1999

NEW
2000
    std::lock_guard<std::mutex> lg{_mutex};
×
2001

2002
    if (_tracking_rectangle_callbacks.empty()) {
×
2003
        LogDebug() << "Track rectangle requested with no user callback provided";
×
2004
        return _server_component_impl->make_command_ack_message(
×
2005
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
2006
    }
2007

2008
    CameraServer::TrackRectangle track_rectangle{
×
2009
        command.params.param1, command.params.param2, command.params.param3, command.params.param4};
×
2010

2011
    _last_track_rectangle_command = command;
×
NEW
2012
    _tracking_rectangle_callbacks.queue(track_rectangle, [this](const auto& func) {
×
NEW
2013
        _server_component_impl->call_user_callback(func);
×
NEW
2014
    });
×
2015
    // We don't send an ack but leave that to the user.
2016
    return std::nullopt;
×
UNCOV
2017
}
×
2018

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

NEW
2029
    std::lock_guard<std::mutex> lg{_mutex};
×
2030

2031
    if (_tracking_off_callbacks.empty()) {
×
2032
        LogDebug() << "Tracking off requested with no user callback provided";
×
2033
        return _server_component_impl->make_command_ack_message(
×
2034
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
2035
    }
2036

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

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

2054
    auto message_id = static_cast<uint32_t>(command.params.param1);
×
2055
    auto interval_us = static_cast<int32_t>(command.params.param2);
×
2056
    UNUSED(message_id);
×
2057

2058
    // Interval value of -1 means to disable sending messages
2059
    if (interval_us < 0) {
×
2060
        stop_sending_tracking_status();
×
2061
    } else {
2062
        start_sending_tracking_status(interval_us);
×
2063
    }
2064

2065
    // Always send the "Accepted" result
2066
    return _server_component_impl->make_command_ack_message(
×
2067
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
2068
}
2069

2070
void CameraServerImpl::send_tracking_status_with_interval(uint32_t interval_us)
×
2071
{
2072
    while (true) {
2073
        std::this_thread::sleep_for(std::chrono::microseconds{interval_us});
×
2074
        {
NEW
2075
            std::scoped_lock lg{_mutex};
×
2076
            if (!_sending_tracking_status) {
×
2077
                return;
×
2078
            }
2079
        }
×
2080
        _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
2081
            mavlink_message_t message;
NEW
2082
            std::lock_guard<std::mutex> lg{_mutex};
×
2083

2084
            // The message is filled based on current tracking mode
2085
            switch (_tracking_mode) {
×
2086
                default:
×
2087
                    // Fallthrough
2088
                case TrackingMode::NONE:
2089

2090
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
2091
                        mavlink_address.system_id,
×
2092
                        mavlink_address.component_id,
×
2093
                        channel,
2094
                        &message,
2095
                        CAMERA_TRACKING_STATUS_FLAGS_IDLE,
2096
                        CAMERA_TRACKING_MODE_NONE,
2097
                        CAMERA_TRACKING_TARGET_DATA_NONE,
2098
                        0.0f,
2099
                        0.0f,
2100
                        0.0f,
2101
                        0.0f,
2102
                        0.0f,
2103
                        0.0f,
2104
                        0.0f,
2105
                        0);
2106
                    break;
×
2107
                case TrackingMode::POINT:
×
2108

2109
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
2110
                        mavlink_address.system_id,
×
2111
                        mavlink_address.component_id,
×
2112
                        channel,
2113
                        &message,
2114
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
2115
                        CAMERA_TRACKING_MODE_POINT,
2116
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
2117
                        _tracked_point.point_x,
2118
                        _tracked_point.point_y,
2119
                        _tracked_point.radius,
2120
                        0.0f,
2121
                        0.0f,
2122
                        0.0f,
2123
                        0.0f,
2124
                        0);
2125
                    break;
×
2126

2127
                case TrackingMode::RECTANGLE:
×
2128

2129
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
2130
                        mavlink_address.system_id,
×
2131
                        mavlink_address.component_id,
×
2132
                        channel,
2133
                        &message,
2134
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
2135
                        CAMERA_TRACKING_MODE_RECTANGLE,
2136
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
2137
                        0.0f,
2138
                        0.0f,
2139
                        0.0f,
2140
                        _tracked_rectangle.top_left_corner_x,
2141
                        _tracked_rectangle.top_left_corner_y,
2142
                        _tracked_rectangle.bottom_right_corner_x,
2143
                        _tracked_rectangle.bottom_right_corner_y,
2144
                        0);
2145
                    break;
×
2146
            }
2147
            return message;
×
2148
        });
×
2149
    }
×
2150
}
2151

2152
void CameraServerImpl::start_sending_tracking_status(uint32_t interval_ms)
×
2153
{
2154
    // Stop sending status with the old interval
2155
    stop_sending_tracking_status();
×
2156

NEW
2157
    std::lock_guard<std::mutex> lg{_mutex};
×
2158
    _sending_tracking_status = true;
×
2159
    _tracking_status_sending_thread =
×
2160
        std::thread{&CameraServerImpl::send_tracking_status_with_interval, this, interval_ms};
×
2161
}
×
2162

2163
void CameraServerImpl::stop_sending_tracking_status()
×
2164
{
2165
    // Firstly, ask the other thread to stop sending the status
2166
    {
NEW
2167
        std::scoped_lock lg{_mutex};
×
2168
        _sending_tracking_status = false;
×
2169
    }
×
2170
    // If the thread was active, wait for it to finish
2171
    if (_tracking_status_sending_thread.joinable()) {
×
2172
        _tracking_status_sending_thread.join();
×
2173
    }
2174
}
×
2175

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