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

mavlink / MAVSDK / 16461829498

23 Jul 2025 04:50AM UTC coverage: 45.189% (+0.1%) from 45.093%
16461829498

Pull #2621

github

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

46 of 132 new or added lines in 1 file covered. (34.85%)

4 existing lines in 4 files now uncovered.

15431 of 34148 relevant lines covered (45.19%)

290.84 hits per line

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

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

4
namespace mavsdk {
5

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

240
        return true;
×
241
    }
242

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

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

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

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

254
    return true;
18✔
255
}
256

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

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

267
    // TODO: validate information.definition_file_uri
268

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

406
    } // Release mutex
4✔
407

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

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

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

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

428
CameraServer::Result
429
CameraServerImpl::respond_start_video(CameraServer::CameraFeedback start_video_feedback)
×
430
{
NEW
431
    bool should_send_capture_status = false;
×
432

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

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

NEW
465
    if (should_send_capture_status) {
×
NEW
466
        send_capture_status();
×
467
    }
468

NEW
469
    return CameraServer::Result::Success;
×
470
}
471

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

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

485
CameraServer::Result
486
CameraServerImpl::respond_stop_video(CameraServer::CameraFeedback stop_video_feedback)
×
487
{
NEW
488
    bool should_send_capture_status = false;
×
489

490
    {
NEW
491
        std::lock_guard<std::mutex> lg{_mutex};
×
492

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

NEW
521
    if (should_send_capture_status) {
×
NEW
522
        send_capture_status();
×
523
    }
524

NEW
525
    return CameraServer::Result::Success;
×
526
}
527

528
CameraServer::StartVideoStreamingHandle CameraServerImpl::subscribe_start_video_streaming(
×
529
    const CameraServer::StartVideoStreamingCallback& callback)
530
{
531
    std::lock_guard<std::mutex> lg{_mutex};
×
532
    return _start_video_streaming_callbacks.subscribe(callback);
×
533
}
×
534

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

542
CameraServer::Result CameraServerImpl::respond_start_video_streaming(
×
543
    CameraServer::CameraFeedback start_video_streaming_feedback)
544
{
545
    std::lock_guard<std::mutex> lg{_mutex};
×
546

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

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

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

587
CameraServer::Result CameraServerImpl::respond_stop_video_streaming(
×
588
    CameraServer::CameraFeedback stop_video_streaming_feedback)
589
{
590
    std::lock_guard<std::mutex> lg{_mutex};
×
591

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

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

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

631
CameraServer::Result
632
CameraServerImpl::respond_set_mode(CameraServer::CameraFeedback set_mode_feedback)
2✔
633
{
634
    std::lock_guard<std::mutex> lg{_mutex};
2✔
635

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

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

669
void CameraServerImpl::unsubscribe_storage_information(
×
670
    CameraServer::StorageInformationHandle handle)
671
{
672
    std::lock_guard<std::mutex> lg{_mutex};
×
673
    _storage_information_callbacks.unsubscribe(handle);
×
674
}
×
675

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

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

708
    const uint8_t storage_count = 1;
2✔
709

710
    const float total_capacity = storage_information.total_storage_mib;
2✔
711
    const float used_capacity = storage_information.used_storage_mib;
2✔
712
    const float available_capacity = storage_information.available_storage_mib;
2✔
713
    const float read_speed = storage_information.read_speed_mib_s;
2✔
714
    const float write_speed = storage_information.write_speed_mib_s;
2✔
715

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

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

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

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

780
    return CameraServer::Result::Success;
2✔
781
}
2✔
782

783
CameraServer::CaptureStatusHandle
784
CameraServerImpl::subscribe_capture_status(const CameraServer::CaptureStatusCallback& callback)
×
785
{
NEW
786
    CameraServer::CaptureStatusHandle handle;
×
NEW
787
    bool should_start_timer = false;
×
788

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

NEW
795
    if (should_start_timer) {
×
NEW
796
        start_sending_capture_status();
×
797
    }
798

NEW
799
    return handle;
×
800
}
801

802
void CameraServerImpl::unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle)
×
803
{
NEW
804
    bool should_stop_timer = false;
×
805

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

NEW
812
    if (should_stop_timer) {
×
NEW
813
        stop_sending_capture_status();
×
814
    }
UNCOV
815
}
×
816

817
CameraServer::Result CameraServerImpl::respond_capture_status(
×
818
    CameraServer::CameraFeedback capture_status_feedback,
819
    CameraServer::CaptureStatus capture_status)
820
{
821
    {
822
        std::lock_guard<std::mutex> lg{_mutex};
×
823

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

850
        _capture_status = capture_status;
×
851
    }
×
852

853
    send_capture_status();
×
854

855
    return CameraServer::Result::Success;
×
856
}
857

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

870
CameraServer::Result
871
CameraServerImpl::respond_format_storage(CameraServer::CameraFeedback format_storage_feedback)
1✔
872
{
873
    std::lock_guard<std::mutex> lg{_mutex};
1✔
874

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

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

908
void CameraServerImpl::unsubscribe_reset_settings(CameraServer::ResetSettingsHandle handle)
×
909
{
910
    std::lock_guard<std::mutex> lg{_mutex};
×
911
    _reset_settings_callbacks.unsubscribe(handle);
×
912
}
×
913

914
CameraServer::Result
915
CameraServerImpl::respond_reset_settings(CameraServer::CameraFeedback reset_settings_feedback)
1✔
916
{
917
    std::lock_guard<std::mutex> lg{_mutex};
1✔
918

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

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

952
void CameraServerImpl::unsubscribe_tracking_point_command(
×
953
    CameraServer::TrackingPointCommandHandle handle)
954
{
955
    std::lock_guard<std::mutex> lg{_mutex};
×
956
    _tracking_point_callbacks.unsubscribe(handle);
×
957
}
×
958

959
CameraServer::Result CameraServerImpl::respond_tracking_point_command(
×
960
    CameraServer::CameraFeedback tracking_point_feedback)
961
{
962
    std::lock_guard<std::mutex> lg{_mutex};
×
963

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

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

998
void CameraServerImpl::unsubscribe_tracking_rectangle_command(
×
999
    CameraServer::TrackingRectangleCommandHandle handle)
1000
{
1001
    std::lock_guard<std::mutex> lg{_mutex};
×
1002
    _tracking_rectangle_callbacks.unsubscribe(handle);
×
1003
}
×
1004

1005
CameraServer::Result CameraServerImpl::respond_tracking_rectangle_command(
×
1006
    CameraServer::CameraFeedback tracking_rectangle_feedback)
1007
{
1008
    std::lock_guard<std::mutex> lg{_mutex};
×
1009

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

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

1044
void CameraServerImpl::unsubscribe_tracking_off_command(
×
1045
    CameraServer::TrackingOffCommandHandle handle)
1046
{
1047
    std::lock_guard<std::mutex> lg{_mutex};
×
1048
    _tracking_off_callbacks.unsubscribe(handle);
×
1049
}
×
1050

1051
CameraServer::Result
1052
CameraServerImpl::respond_tracking_off_command(CameraServer::CameraFeedback tracking_off_feedback)
×
1053
{
1054
    std::lock_guard<std::mutex> lg{_mutex};
×
1055

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

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

1088
    _last_interval_index = index;
1✔
1089

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

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

1101
            if (*remaining == 0) {
3✔
1102
                stop_image_capture_interval();
×
1103
            }
1104
        },
3✔
1105
        interval_s);
1106

1107
    _is_image_capture_interval_set = true;
1✔
1108
    _image_capture_timer_interval_s = interval_s;
1✔
1109
}
1✔
1110

1111
void CameraServerImpl::stop_image_capture_interval()
12✔
1112
{
1113
    _server_component_impl->remove_call_every(_image_capture_timer_cookie);
12✔
1114

1115
    std::lock_guard<std::mutex> lg{_mutex};
12✔
1116
    _is_image_capture_interval_set = false;
12✔
1117
    _image_capture_timer_interval_s = 0;
12✔
1118
}
12✔
1119

1120
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_information_request(
×
1121
    const MavlinkCommandReceiver::CommandLong& command)
1122
{
1123
    LogDebug() << "Camera info request";
×
1124

1125
    if (static_cast<int>(command.params.param1) == 0) {
×
1126
        return _server_component_impl->make_command_ack_message(
×
1127
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1128
    }
1129

1130
    return send_camera_information(command);
×
1131
}
1132

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

1140
        case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS:
9✔
1141
            send_capture_status();
9✔
1142
            return _server_component_impl->make_command_ack_message(
18✔
1143
                command, MAV_RESULT::MAV_RESULT_ACCEPTED);
18✔
1144

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

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

1157
    if (!_is_information_set) {
9✔
1158
        return _server_component_impl->make_command_ack_message(
×
1159
            command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED);
×
1160
    }
1161

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

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

1172
    // capability flags are determined by subscriptions
1173
    uint32_t capability_flags{};
9✔
1174

1175
    if (!_take_photo_callbacks.empty()) {
9✔
1176
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE;
2✔
1177
    }
1178

1179
    if (!_start_video_callbacks.empty()) {
9✔
1180
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
×
1181
    }
1182

1183
    if (!_set_mode_callbacks.empty()) {
9✔
1184
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES;
2✔
1185
    }
1186

1187
    if (_information.image_in_video_mode_supported) {
9✔
1188
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE;
×
1189
    }
1190

1191
    if (_information.video_in_image_mode_supported) {
9✔
1192
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE;
×
1193
    }
1194

1195
    if (_is_video_streaming_set) {
9✔
1196
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM;
1✔
1197
    }
1198

1199
    if (!_tracking_point_callbacks.empty()) {
9✔
1200
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT;
×
1201
    }
1202

1203
    if (!_tracking_rectangle_callbacks.empty()) {
9✔
1204
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE;
×
1205
    }
1206

1207
    if (!_zoom_range_callbacks.empty() || !_zoom_in_start_callbacks.empty() ||
18✔
1208
        !_zoom_out_start_callbacks.empty()) {
9✔
1209
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM;
×
1210
    }
1211

1212
    _information.vendor_name.resize(sizeof(mavlink_camera_information_t::vendor_name));
9✔
1213
    _information.model_name.resize(sizeof(mavlink_camera_information_t::model_name));
9✔
1214
    _information.definition_file_uri.resize(
9✔
1215
        sizeof(mavlink_camera_information_t::cam_definition_uri));
1216

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

1242
    return std::nullopt;
9✔
1243
}
9✔
1244

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

1250
    if (!settings) {
9✔
1251
        return _server_component_impl->make_command_ack_message(
×
1252
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1253
    }
1254

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

1261
    // unsupported
1262
    const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE;
9✔
1263
    const float zoom_level = 0;
9✔
1264
    const float focus_level = 0;
9✔
1265

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

1282
    // ack was already sent
1283
    return std::nullopt;
9✔
1284
}
1285

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

1292
    if (!information) {
16✔
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};
16✔
1298

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

1306
    // TODO may need support multi storage id
1307
    _last_storage_id = storage_id;
2✔
1308

1309
    _last_storage_information_command = command;
2✔
1310

1311
    _storage_information_callbacks.queue(
2✔
1312
        storage_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
2✔
1313

1314
    // ack will be sent later in respond_storage_information
1315
    return std::nullopt;
2✔
1316
}
16✔
1317

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

1325
    UNUSED(format);
1✔
1326
    UNUSED(reset_image_log);
1✔
1327

1328
    std::lock_guard<std::mutex> lg{_mutex};
1✔
1329

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

1336
    _last_format_storage_command = command;
1✔
1337

1338
    _format_storage_callbacks.queue(
1✔
1339
        storage_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
1✔
1340

1341
    return std::nullopt;
1✔
1342
}
1✔
1343

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

1349
    if (!capture_status) {
×
1350
        return _server_component_impl->make_command_ack_message(
×
1351
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1352
    }
1353

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

1361
    _last_capture_status_command = command;
×
1362

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

1367
    // ack was already sent
1368
    return std::nullopt;
×
1369
}
×
1370

1371
void CameraServerImpl::send_capture_status()
13✔
1372
{
1373
    std::lock_guard<std::mutex> lg{_mutex};
13✔
1374

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

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

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

1399
    const uint32_t recording_time_ms =
13✔
1400
        static_cast<uint32_t>(static_cast<double>(_capture_status.recording_time_s) * 1e3);
13✔
1401
    const float available_capacity = _capture_status.available_capacity_mib;
13✔
1402

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

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

1427
    UNUSED(reset);
1✔
1428

1429
    std::lock_guard<std::mutex> lg{_mutex};
1✔
1430

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

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

1441
    return std::nullopt;
1✔
1442
}
1✔
1443

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

1449
    std::lock_guard<std::mutex> lg{_mutex};
2✔
1450

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

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

1465
    if (convert_camera_mode == CameraServer::Mode::Unknown) {
2✔
1466
        return _server_component_impl->make_command_ack_message(
×
1467
            command, MAV_RESULT::MAV_RESULT_DENIED);
×
1468
    }
1469

1470
    _last_set_mode_command = command;
2✔
1471

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

1476
    return std::nullopt;
2✔
1477
}
2✔
1478

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

1485
    std::lock_guard<std::mutex> lg{_mutex};
×
1486

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

1494
    auto unsupported = [&]() {
×
1495
        LogWarn() << "unsupported set camera zoom type (" << (int)zoom_type << ") request";
×
1496
    };
×
1497

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

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

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

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

1578
    UNUSED(focus_type);
×
1579
    UNUSED(focus_value);
×
1580

1581
    LogDebug() << "unsupported set camera focus request";
×
1582

1583
    return _server_component_impl->make_command_ack_message(
×
1584
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1585
}
1586

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

1593
    UNUSED(storage_id);
×
1594
    UNUSED(usage);
×
1595

1596
    LogDebug() << "unsupported set storage usage request";
×
1597

1598
    return _server_component_impl->make_command_ack_message(
×
1599
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1600
}
1601

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

1609
    LogDebug() << "received image start capture request - interval: " << +interval_s
6✔
1610
               << " total: " << +total_images << " index: " << +seq_number;
6✔
1611

1612
    // TODO: validate parameters and return MAV_RESULT_DENIED not valid
1613

1614
    stop_image_capture_interval();
2✔
1615

1616
    std::lock_guard<std::mutex> lg{_mutex};
2✔
1617

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

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

1631
        _last_take_photo_command = command;
1✔
1632

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

1637
        return std::nullopt;
1✔
1638
    }
1639

1640
    start_image_capture_interval(interval_s, total_images, seq_number);
1✔
1641

1642
    return _server_component_impl->make_command_ack_message(
2✔
1643
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
2✔
1644
}
2✔
1645

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

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

1655
    return _server_component_impl->make_command_ack_message(
2✔
1656
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
2✔
1657
}
1658

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

1664
    UNUSED(seq_number);
×
1665

1666
    LogDebug() << "unsupported image capture request";
×
1667

1668
    return _server_component_impl->make_command_ack_message(
×
1669
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1670
}
1671

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

1678
    UNUSED(status_frequency);
×
1679

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

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

1688
    _last_start_video_command = command;
×
1689
    _start_video_callbacks.queue(
×
1690
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1691

1692
    return std::nullopt;
×
1693
}
×
1694

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

1700
    std::lock_guard<std::mutex> lg{_mutex};
×
1701

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

1708
    _last_stop_video_command = command;
×
1709
    _stop_video_callbacks.queue(
×
1710
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1711

1712
    return std::nullopt;
×
1713
}
×
1714

1715
std::optional<mavlink_command_ack_t>
1716
CameraServerImpl::process_video_start_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1717
{
1718
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1719

1720
    std::lock_guard<std::mutex> lg{_mutex};
×
1721

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

1728
    _last_start_video_streaming_command = command;
×
1729
    _start_video_streaming_callbacks.queue(
×
1730
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1731

1732
    return std::nullopt;
×
1733
}
×
1734

1735
std::optional<mavlink_command_ack_t>
1736
CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1737
{
1738
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1739

1740
    std::lock_guard<std::mutex> lg{_mutex};
×
1741

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

1748
    _last_stop_video_streaming_command = command;
×
1749
    _stop_video_streaming_callbacks.queue(
×
1750
        stream_id, [this](const auto& func) { _server_component_impl->call_user_callback(func); });
×
1751

1752
    return std::nullopt;
×
1753
}
×
1754

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

1760
    UNUSED(stream_id);
15✔
1761

1762
    std::lock_guard<std::mutex> lg{_mutex};
15✔
1763

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

1770
        const char name[32] = "";
1✔
1771

1772
        _video_streaming.rtsp_uri.resize(sizeof(mavlink_video_stream_information_t::uri));
1✔
1773

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

1794
        _server_component_impl->send_message(msg);
1✔
1795

1796
        // Ack already sent.
1797
        return std::nullopt;
1✔
1798

1799
    } else {
1800
        return _server_component_impl->make_command_ack_message(
28✔
1801
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
28✔
1802
    }
1803
}
15✔
1804

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

1810
    UNUSED(stream_id);
17✔
1811

1812
    std::lock_guard<std::mutex> lg{_mutex};
17✔
1813

1814
    if (!_is_video_streaming_set) {
17✔
1815
        return _server_component_impl->make_command_ack_message(
32✔
1816
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
32✔
1817
    }
1818

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

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

1840
    // ack was already sent
1841
    return std::nullopt;
1✔
1842
}
17✔
1843

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

1851
void CameraServerImpl::unsubscribe_zoom_in_start(CameraServer::ZoomInStartHandle handle)
×
1852
{
1853
    std::lock_guard<std::mutex> lg{_mutex};
×
1854
    _zoom_in_start_callbacks.unsubscribe(handle);
×
1855
}
×
1856

1857
CameraServer::Result
1858
CameraServerImpl::respond_zoom_in_start(CameraServer::CameraFeedback zoom_in_start_feedback)
×
1859
{
1860
    std::lock_guard<std::mutex> lg{_mutex};
×
1861

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

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

1895
void CameraServerImpl::unsubscribe_zoom_out_start(CameraServer::ZoomOutStartHandle handle)
×
1896
{
1897
    std::lock_guard<std::mutex> lg{_mutex};
×
1898
    _zoom_out_start_callbacks.unsubscribe(handle);
×
1899
}
×
1900

1901
CameraServer::Result
1902
CameraServerImpl::respond_zoom_out_start(CameraServer::CameraFeedback zoom_out_start_feedback)
×
1903
{
1904
    std::lock_guard<std::mutex> lg{_mutex};
×
1905

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

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

1939
void CameraServerImpl::unsubscribe_zoom_stop(CameraServer::ZoomStopHandle handle)
×
1940
{
1941
    std::lock_guard<std::mutex> lg{_mutex};
×
1942
    _zoom_stop_callbacks.unsubscribe(handle);
×
1943
}
×
1944

1945
CameraServer::Result
1946
CameraServerImpl::respond_zoom_stop(CameraServer::CameraFeedback zoom_stop_feedback)
×
1947
{
1948
    std::lock_guard<std::mutex> lg{_mutex};
×
1949

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

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

1983
void CameraServerImpl::unsubscribe_zoom_range(CameraServer::ZoomRangeHandle handle)
×
1984
{
1985
    std::lock_guard<std::mutex> lg{_mutex};
×
1986
    _zoom_range_callbacks.unsubscribe(handle);
×
1987
}
×
1988

1989
CameraServer::Result
1990
CameraServerImpl::respond_zoom_range(CameraServer::CameraFeedback zoom_range_feedback)
×
1991
{
1992
    std::lock_guard<std::mutex> lg{_mutex};
×
1993

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

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

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

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

2038
    CameraServer::TrackPoint track_point{
×
2039
        command.params.param1, command.params.param2, command.params.param3};
×
2040

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

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

2059
    std::lock_guard<std::mutex> lg{_mutex};
×
2060

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

2067
    CameraServer::TrackRectangle track_rectangle{
×
2068
        command.params.param1, command.params.param2, command.params.param3, command.params.param4};
×
2069

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

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

2088
    std::lock_guard<std::mutex> lg{_mutex};
×
2089

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

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

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

2113
    auto message_id = static_cast<uint32_t>(command.params.param1);
×
2114
    auto interval_us = static_cast<int32_t>(command.params.param2);
×
2115
    UNUSED(message_id);
×
2116

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

2124
    // Always send the "Accepted" result
2125
    return _server_component_impl->make_command_ack_message(
×
2126
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
2127
}
2128

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

2143
            // The message is filled based on current tracking mode
2144
            switch (_tracking_mode) {
×
2145
                default:
×
2146
                    // Fallthrough
2147
                case TrackingMode::NONE:
2148

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

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

2186
                case TrackingMode::RECTANGLE:
×
2187

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

2211
void CameraServerImpl::start_sending_tracking_status(uint32_t interval_ms)
×
2212
{
2213
    // Stop sending status with the old interval
2214
    stop_sending_tracking_status();
×
2215

2216
    std::lock_guard<std::mutex> lg{_mutex};
×
2217
    _sending_tracking_status = true;
×
2218
    _tracking_status_sending_thread =
×
2219
        std::thread{&CameraServerImpl::send_tracking_status_with_interval, this, interval_ms};
×
2220
}
×
2221

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

NEW
2235
void CameraServerImpl::start_sending_capture_status()
×
2236
{
NEW
2237
    _capture_status_timer_cookie = _server_component_impl->add_call_every(
×
NEW
2238
        [this]() { send_capture_status(); }, CAPTURE_STATUS_INTERVAL_S);
×
NEW
2239
}
×
2240

2241
void CameraServerImpl::stop_sending_capture_status()
9✔
2242
{
2243
    _server_component_impl->remove_call_every(_capture_status_timer_cookie);
9✔
2244
}
9✔
2245

2246
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2025 Coveralls, Inc