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

mavlink / MAVSDK / 15379848700

01 Jun 2025 09:59PM UTC coverage: 44.311% (+0.05%) from 44.257%
15379848700

push

github

web-flow
Merge pull request #2591 from mavlink/pr-camera-server-deadlock

Fix camera_serve lockup

0 of 21 new or added lines in 1 file covered. (0.0%)

1 existing line in 1 file now uncovered.

14900 of 33626 relevant lines covered (44.31%)

291.84 hits per line

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

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

4
namespace mavsdk {
5

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

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

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

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

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

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

171
void CameraServerImpl::deinit()
9✔
172
{
173
    stop_image_capture_interval();
9✔
174
    _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
{
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
{
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
{
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
{
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
{
407
    std::lock_guard<std::mutex> lg{_mutex};
×
408
    return _start_video_callbacks.subscribe(callback);
×
409
}
×
410

411
void CameraServerImpl::unsubscribe_start_video(CameraServer::StartVideoHandle handle)
×
412
{
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
{
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
    }
446
}
×
447

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

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

461
CameraServer::Result
462
CameraServerImpl::respond_stop_video(CameraServer::CameraFeedback stop_video_feedback)
×
463
{
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
    }
490
}
×
491

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

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

506
CameraServer::Result CameraServerImpl::respond_start_video_streaming(
×
507
    CameraServer::CameraFeedback start_video_streaming_feedback)
508
{
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
    }
535
}
×
536

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

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

551
CameraServer::Result CameraServerImpl::respond_stop_video_streaming(
×
552
    CameraServer::CameraFeedback stop_video_streaming_feedback)
553
{
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
    }
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
{
636
    std::lock_guard<std::mutex> lg{_mutex};
×
637
    _storage_information_callbacks.unsubscribe(handle);
×
638
}
×
639

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

646
    switch (storage_information_feedback) {
2✔
647
        default:
×
648
            // Fallthrough
649
        case CameraServer::CameraFeedback::Unknown:
650
            return CameraServer::Result::Error;
×
651
        case CameraServer::CameraFeedback::Ok: {
2✔
652
            auto command_ack = _server_component_impl->make_command_ack_message(
2✔
653
                _last_storage_information_command, MAV_RESULT_ACCEPTED);
2✔
654
            _server_component_impl->send_command_ack(command_ack);
2✔
655
            // break and send storage information
656
            break;
2✔
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;
2✔
673

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

680
    auto status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
2✔
681
    switch (storage_information.storage_status) {
2✔
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:
2✔
689
            status = STORAGE_STATUS::STORAGE_STATUS_READY;
2✔
690
            break;
2✔
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;
2✔
697
    switch (storage_information.storage_type) {
2✔
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:
2✔
714
            break;
2✔
715
    }
716

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

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

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

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

754
void CameraServerImpl::unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle)
×
755
{
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
{
764
    {
NEW
765
        std::lock_guard<std::mutex> lg{_mutex};
×
766

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

NEW
793
        _capture_status = capture_status;
×
NEW
794
    }
×
795

796
    send_capture_status();
×
797

798
    return CameraServer::Result::Success;
×
799
}
800

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1031
    _last_interval_index = index;
1✔
1032

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

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

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

1050
    _is_image_capture_interval_set = true;
1✔
1051
    _image_capture_timer_interval_s = interval_s;
1✔
1052
}
1✔
1053

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

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

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

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

1073
    return send_camera_information(command);
×
1074
}
1075

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

1083
        case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS:
9✔
1084
            send_capture_status();
9✔
1085
            return _server_component_impl->make_command_ack_message(
18✔
1086
                command, MAV_RESULT::MAV_RESULT_ACCEPTED);
18✔
1087

1088
        default:
79✔
1089
            LogWarn() << "Got unknown request message!";
79✔
1090
            return _server_component_impl->make_command_ack_message(
158✔
1091
                command, MAV_RESULT::MAV_RESULT_DENIED);
158✔
1092
    }
1093
}
1094

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

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

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

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

1115
    // capability flags are determined by subscriptions
1116
    uint32_t capability_flags{};
9✔
1117

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

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

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

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

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

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

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

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

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

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

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

1185
    return std::nullopt;
9✔
1186
}
9✔
1187

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

1193
    if (!settings) {
9✔
1194
        return _server_component_impl->make_command_ack_message(
×
1195
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1196
    }
1197

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

1204
    // unsupported
1205
    const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE;
9✔
1206
    const float zoom_level = 0;
9✔
1207
    const float focus_level = 0;
9✔
1208

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

1225
    // ack was already sent
1226
    return std::nullopt;
9✔
1227
}
1228

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

1235
    if (!information) {
16✔
1236
        return _server_component_impl->make_command_ack_message(
×
1237
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1238
    }
1239

1240
    std::lock_guard<std::mutex> lg{_mutex};
16✔
1241

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

1249
    // TODO may need support multi storage id
1250
    _last_storage_id = storage_id;
2✔
1251

1252
    _last_storage_information_command = command;
2✔
1253

1254
    _storage_information_callbacks.queue(
2✔
1255
        storage_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
2✔
1256

1257
    // ack will be sent later in respond_storage_information
1258
    return std::nullopt;
2✔
1259
}
16✔
1260

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

1268
    UNUSED(format);
1✔
1269
    UNUSED(reset_image_log);
1✔
1270

1271
    std::lock_guard<std::mutex> lg{_mutex};
1✔
1272

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

1279
    _last_format_storage_command = command;
1✔
1280

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

1284
    return std::nullopt;
1✔
1285
}
1✔
1286

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

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

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

1304
    _last_capture_status_command = command;
×
1305

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

1310
    // ack was already sent
1311
    return std::nullopt;
×
1312
}
×
1313

1314
void CameraServerImpl::send_capture_status()
9✔
1315
{
1316
    std::lock_guard<std::mutex> lg{_mutex};
9✔
1317

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

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

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

1342
    const uint32_t recording_time_ms =
9✔
1343
        static_cast<uint32_t>(static_cast<double>(_capture_status.recording_time_s) * 1e3);
9✔
1344
    const float available_capacity = _capture_status.available_capacity_mib;
9✔
1345

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

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

1370
    UNUSED(reset);
1✔
1371

1372
    std::lock_guard<std::mutex> lg{_mutex};
1✔
1373

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

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

1384
    return std::nullopt;
1✔
1385
}
1✔
1386

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

1392
    std::lock_guard<std::mutex> lg{_mutex};
2✔
1393

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

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

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

1413
    _last_set_mode_command = command;
2✔
1414

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

1419
    return std::nullopt;
2✔
1420
}
2✔
1421

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

1428
    std::lock_guard<std::mutex> lg{_mutex};
×
1429

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

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

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

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

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

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

1521
    UNUSED(focus_type);
×
1522
    UNUSED(focus_value);
×
1523

1524
    LogDebug() << "unsupported set camera focus request";
×
1525

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

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

1536
    UNUSED(storage_id);
×
1537
    UNUSED(usage);
×
1538

1539
    LogDebug() << "unsupported set storage usage request";
×
1540

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

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

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

1555
    // TODO: validate parameters and return MAV_RESULT_DENIED not valid
1556

1557
    stop_image_capture_interval();
2✔
1558

1559
    std::lock_guard<std::mutex> lg{_mutex};
2✔
1560

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

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

1574
        _last_take_photo_command = command;
1✔
1575

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

1580
        return std::nullopt;
1✔
1581
    }
1582

1583
    start_image_capture_interval(interval_s, total_images, seq_number);
1✔
1584

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

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

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

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

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

1607
    UNUSED(seq_number);
×
1608

1609
    LogDebug() << "unsupported image capture request";
×
1610

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

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

1621
    UNUSED(status_frequency);
×
1622

1623
    std::lock_guard<std::mutex> lg{_mutex};
×
1624

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

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

1635
    return std::nullopt;
×
1636
}
×
1637

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

1643
    std::lock_guard<std::mutex> lg{_mutex};
×
1644

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

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

1655
    return std::nullopt;
×
1656
}
×
1657

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

1663
    std::lock_guard<std::mutex> lg{_mutex};
×
1664

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

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

1675
    return std::nullopt;
×
1676
}
×
1677

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

1683
    std::lock_guard<std::mutex> lg{_mutex};
×
1684

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

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

1695
    return std::nullopt;
×
1696
}
×
1697

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

1703
    UNUSED(stream_id);
15✔
1704

1705
    std::lock_guard<std::mutex> lg{_mutex};
15✔
1706

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

1713
        const char name[32] = "";
1✔
1714

1715
        _video_streaming.rtsp_uri.resize(sizeof(mavlink_video_stream_information_t::uri));
1✔
1716

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

1737
        _server_component_impl->send_message(msg);
1✔
1738

1739
        // Ack already sent.
1740
        return std::nullopt;
1✔
1741

1742
    } else {
1743
        return _server_component_impl->make_command_ack_message(
28✔
1744
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
28✔
1745
    }
1746
}
15✔
1747

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

1753
    UNUSED(stream_id);
17✔
1754

1755
    std::lock_guard<std::mutex> lg{_mutex};
17✔
1756

1757
    if (!_is_video_streaming_set) {
17✔
1758
        return _server_component_impl->make_command_ack_message(
32✔
1759
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
32✔
1760
    }
1761

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

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

1783
    // ack was already sent
1784
    return std::nullopt;
1✔
1785
}
17✔
1786

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1973
    std::lock_guard<std::mutex> lg{_mutex};
×
1974

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

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

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

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

2002
    std::lock_guard<std::mutex> lg{_mutex};
×
2003

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

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

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

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

2031
    std::lock_guard<std::mutex> lg{_mutex};
×
2032

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

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

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

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

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

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

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

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

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

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

2129
                case TrackingMode::RECTANGLE:
×
2130

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

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

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

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

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

© 2026 Coveralls, Inc