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

mavlink / MAVSDK / 12918137557

22 Jan 2025 10:20PM UTC coverage: 44.611% (-0.04%) from 44.646%
12918137557

push

github

web-flow
Merge pull request #2495 from chenrui333/macos-rpath-issue

fix `rpath` issue for `mavsdk_server` macos build

14589 of 32703 relevant lines covered (44.61%)

284.6 hits per line

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

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

4
namespace mavsdk {
5

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

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

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

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

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

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

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

177
bool CameraServerImpl::is_command_sender_ok(const MavlinkCommandReceiver::CommandLong& command)
×
178
{
179
    if (command.target_system_id != 0 &&
×
180
        command.target_system_id != _server_component_impl->get_own_system_id()) {
×
181
        return false;
×
182
    } else {
183
        return true;
×
184
    }
185
}
186

187
void CameraServerImpl::set_tracking_point_status(CameraServer::TrackPoint tracked_point)
×
188
{
189
    std::lock_guard<std::mutex> lg{_tracking_status_mutex};
×
190
    _tracking_mode = TrackingMode::POINT;
×
191
    _tracked_point = tracked_point;
×
192
}
×
193

194
void CameraServerImpl::set_tracking_rectangle_status(CameraServer::TrackRectangle tracked_rectangle)
×
195
{
196
    std::lock_guard<std::mutex> lg{_tracking_status_mutex};
×
197
    _tracking_mode = TrackingMode::RECTANGLE;
×
198
    _tracked_rectangle = tracked_rectangle;
×
199
}
×
200

201
void CameraServerImpl::set_tracking_off_status()
×
202
{
203
    std::lock_guard<std::mutex> lg{_tracking_status_mutex};
×
204
    _tracking_mode = TrackingMode::NONE;
×
205
}
×
206

207
bool CameraServerImpl::parse_version_string(const std::string& version_str)
9✔
208
{
209
    uint32_t unused;
9✔
210

211
    return parse_version_string(version_str, unused);
9✔
212
}
213

214
bool CameraServerImpl::parse_version_string(const std::string& version_str, uint32_t& version)
18✔
215
{
216
    // empty string means no version
217
    if (version_str.empty()) {
18✔
218
        version = 0;
×
219

220
        return true;
×
221
    }
222

223
    uint8_t major{}, minor{}, patch{}, dev{};
18✔
224

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

227
    if (ret == EOF) {
18✔
228
        return false;
×
229
    }
230

231
    // pack version according to MAVLINK spec
232
    version = dev << 24 | patch << 16 | minor << 8 | major;
18✔
233

234
    return true;
18✔
235
}
236

237
CameraServer::Result CameraServerImpl::set_information(CameraServer::Information information)
9✔
238
{
239
    if (!parse_version_string(information.firmware_version)) {
9✔
240
        LogDebug() << "incorrectly formatted firmware version string: "
×
241
                   << information.firmware_version;
×
242
        return CameraServer::Result::WrongArgument;
×
243
    }
244

245
    // TODO: validate information.definition_file_uri
246

247
    _is_information_set = true;
9✔
248
    _information = information;
9✔
249

250
    return CameraServer::Result::Success;
9✔
251
}
252

253
CameraServer::Result
254
CameraServerImpl::set_video_streaming(CameraServer::VideoStreaming video_streaming)
1✔
255
{
256
    // TODO: validate uri length
257

258
    _is_video_streaming_set = true;
1✔
259
    _video_streaming = video_streaming;
1✔
260

261
    return CameraServer::Result::Success;
1✔
262
}
263

264
CameraServer::Result CameraServerImpl::set_in_progress(bool in_progress)
×
265
{
266
    _is_image_capture_in_progress = in_progress;
×
267

268
    send_capture_status();
×
269
    return CameraServer::Result::Success;
×
270
}
271

272
CameraServer::TakePhotoHandle
273
CameraServerImpl::subscribe_take_photo(const CameraServer::TakePhotoCallback& callback)
2✔
274
{
275
    return _take_photo_callbacks.subscribe(callback);
2✔
276
}
277

278
void CameraServerImpl::unsubscribe_take_photo(CameraServer::TakePhotoHandle handle)
×
279
{
280
    _take_photo_callbacks.unsubscribe(handle);
×
281
}
×
282

283
CameraServer::Result CameraServerImpl::respond_take_photo(
4✔
284
    CameraServer::CameraFeedback take_photo_feedback, CameraServer::CaptureInfo capture_info)
285
{
286
    // If capture_info.index == INT32_MIN, it means this was an interval
287
    // capture rather than a single image capture.
288
    if (capture_info.index != INT32_MIN) {
4✔
289
        // We expect each capture to be the next sequential number.
290
        // If _image_capture_count == 0, we ignore since it means that this is
291
        // the first photo since the plugin was initialized.
292
        if (_image_capture_count != 0 && capture_info.index != _image_capture_count + 1) {
4✔
293
            LogErr() << "unexpected image index, expecting " << +(_image_capture_count + 1)
×
294
                     << " but was " << +capture_info.index;
×
295
        }
296

297
        _image_capture_count = capture_info.index;
4✔
298
    }
299

300
    switch (take_photo_feedback) {
4✔
301
        default:
×
302
            // Fallthrough
303
        case CameraServer::CameraFeedback::Unknown:
304
            return CameraServer::Result::Error;
×
305
        case CameraServer::CameraFeedback::Ok: {
4✔
306
            // Check for error above
307
            auto command_ack = _server_component_impl->make_command_ack_message(
4✔
308
                _last_take_photo_command, MAV_RESULT_ACCEPTED);
4✔
309
            _server_component_impl->send_command_ack(command_ack);
4✔
310
            // Only break and send the captured below.
311
            break;
4✔
312
        }
313
        case CameraServer::CameraFeedback::Busy: {
×
314
            auto command_ack = _server_component_impl->make_command_ack_message(
×
315
                _last_take_photo_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
316
            _server_component_impl->send_command_ack(command_ack);
×
317
            return CameraServer::Result::Success;
×
318
        }
319

320
        case CameraServer::CameraFeedback::Failed: {
×
321
            auto command_ack = _server_component_impl->make_command_ack_message(
×
322
                _last_take_photo_command, MAV_RESULT_FAILED);
×
323
            _server_component_impl->send_command_ack(command_ack);
×
324
            return CameraServer::Result::Success;
×
325
        }
326
    }
327

328
    // REVISIT: Should we cache all CaptureInfo in memory for single image
329
    // captures so that we can respond to requests for lost CAMERA_IMAGE_CAPTURED
330
    // messages without calling back to user code?
331

332
    static const uint8_t camera_id = 0; // deprecated unused field
333

334
    const float attitude_quaternion[] = {
4✔
335
        capture_info.attitude_quaternion.w,
4✔
336
        capture_info.attitude_quaternion.x,
4✔
337
        capture_info.attitude_quaternion.y,
4✔
338
        capture_info.attitude_quaternion.z,
4✔
339
    };
4✔
340

341
    // There needs to be enough data to be copied mavlink internal.
342
    capture_info.file_url.resize(205);
4✔
343

344
    // TODO: this should be a broadcast message
345
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
4✔
346
        mavlink_message_t message{};
4✔
347
        mavlink_msg_camera_image_captured_pack_chan(
12✔
348
            mavlink_address.system_id,
4✔
349
            mavlink_address.component_id,
4✔
350
            channel,
351
            &message,
352
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
4✔
353
            capture_info.time_utc_us,
4✔
354
            camera_id,
355
            static_cast<int32_t>(capture_info.position.latitude_deg * 1e7),
4✔
356
            static_cast<int32_t>(capture_info.position.longitude_deg * 1e7),
4✔
357
            static_cast<int32_t>(capture_info.position.absolute_altitude_m * 1e3f),
4✔
358
            static_cast<int32_t>(capture_info.position.relative_altitude_m * 1e3f),
4✔
359
            attitude_quaternion,
4✔
360
            capture_info.index,
361
            capture_info.is_success,
4✔
362
            capture_info.file_url.c_str());
363
        return message;
4✔
364
    });
365
    LogDebug() << "sent camera image captured msg - index: " << +capture_info.index;
4✔
366

367
    return CameraServer::Result::Success;
4✔
368
}
369

370
CameraServer::StartVideoHandle
371
CameraServerImpl::subscribe_start_video(const CameraServer::StartVideoCallback& callback)
×
372
{
373
    return _start_video_callbacks.subscribe(callback);
×
374
}
375

376
void CameraServerImpl::unsubscribe_start_video(CameraServer::StartVideoHandle handle)
×
377
{
378
    _start_video_callbacks.unsubscribe(handle);
×
379
}
×
380

381
CameraServer::Result
382
CameraServerImpl::respond_start_video(CameraServer::CameraFeedback start_video_feedback)
×
383
{
384
    switch (start_video_feedback) {
×
385
        default:
×
386
            // Fallthrough
387
        case CameraServer::CameraFeedback::Unknown:
388
            return CameraServer::Result::Error;
×
389
        case CameraServer::CameraFeedback::Ok: {
×
390
            auto command_ack = _server_component_impl->make_command_ack_message(
×
391
                _last_start_video_command, MAV_RESULT_ACCEPTED);
×
392
            _server_component_impl->send_command_ack(command_ack);
×
393
            return CameraServer::Result::Success;
×
394
        }
395
        case CameraServer::CameraFeedback::Busy: {
×
396
            auto command_ack = _server_component_impl->make_command_ack_message(
×
397
                _last_start_video_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
398
            _server_component_impl->send_command_ack(command_ack);
×
399
            return CameraServer::Result::Success;
×
400
        }
401
        case CameraServer::CameraFeedback::Failed: {
×
402
            auto command_ack = _server_component_impl->make_command_ack_message(
×
403
                _last_start_video_command, MAV_RESULT_FAILED);
×
404
            _server_component_impl->send_command_ack(command_ack);
×
405
            return CameraServer::Result::Success;
×
406
        }
407
    }
408
}
409

410
CameraServer::StopVideoHandle
411
CameraServerImpl::subscribe_stop_video(const CameraServer::StopVideoCallback& callback)
×
412
{
413
    return _stop_video_callbacks.subscribe(callback);
×
414
}
415

416
void CameraServerImpl::unsubscribe_stop_video(CameraServer::StopVideoHandle handle)
×
417
{
418
    return _stop_video_callbacks.unsubscribe(handle);
×
419
}
420

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

450
CameraServer::StartVideoStreamingHandle CameraServerImpl::subscribe_start_video_streaming(
×
451
    const CameraServer::StartVideoStreamingCallback& callback)
452
{
453
    return _start_video_streaming_callbacks.subscribe(callback);
×
454
}
455

456
void CameraServerImpl::unsubscribe_start_video_streaming(
×
457
    CameraServer::StartVideoStreamingHandle handle)
458
{
459
    return _start_video_streaming_callbacks.unsubscribe(handle);
×
460
}
461

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

491
CameraServer::StopVideoStreamingHandle CameraServerImpl::subscribe_stop_video_streaming(
×
492
    const CameraServer::StopVideoStreamingCallback& callback)
493
{
494
    return _stop_video_streaming_callbacks.subscribe(callback);
×
495
}
496

497
void CameraServerImpl::unsubscribe_stop_video_streaming(
×
498
    CameraServer::StopVideoStreamingHandle handle)
499
{
500
    return _stop_video_streaming_callbacks.unsubscribe(handle);
×
501
}
502

503
CameraServer::Result CameraServerImpl::respond_stop_video_streaming(
×
504
    CameraServer::CameraFeedback stop_video_streaming_feedback)
505
{
506
    switch (stop_video_streaming_feedback) {
×
507
        default:
×
508
            // Fallthrough
509
        case CameraServer::CameraFeedback::Unknown:
510
            return CameraServer::Result::Error;
×
511
        case CameraServer::CameraFeedback::Ok: {
×
512
            auto command_ack = _server_component_impl->make_command_ack_message(
×
513
                _last_stop_video_streaming_command, MAV_RESULT_ACCEPTED);
×
514
            _server_component_impl->send_command_ack(command_ack);
×
515
            return CameraServer::Result::Success;
×
516
        }
517
        case CameraServer::CameraFeedback::Busy: {
×
518
            auto command_ack = _server_component_impl->make_command_ack_message(
×
519
                _last_stop_video_streaming_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
520
            _server_component_impl->send_command_ack(command_ack);
×
521
            return CameraServer::Result::Success;
×
522
        }
523
        case CameraServer::CameraFeedback::Failed: {
×
524
            auto command_ack = _server_component_impl->make_command_ack_message(
×
525
                _last_stop_video_streaming_command, MAV_RESULT_FAILED);
×
526
            _server_component_impl->send_command_ack(command_ack);
×
527
            return CameraServer::Result::Success;
×
528
        }
529
    }
530
}
531

532
CameraServer::SetModeHandle
533
CameraServerImpl::subscribe_set_mode(const CameraServer::SetModeCallback& callback)
2✔
534
{
535
    return _set_mode_callbacks.subscribe(callback);
2✔
536
}
537

538
void CameraServerImpl::unsubscribe_set_mode(CameraServer::SetModeHandle handle)
×
539
{
540
    _set_mode_callbacks.unsubscribe(handle);
×
541
}
×
542

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

572
CameraServer::StorageInformationHandle CameraServerImpl::subscribe_storage_information(
1✔
573
    const CameraServer::StorageInformationCallback& callback)
574
{
575
    return _storage_information_callbacks.subscribe(callback);
1✔
576
}
577

578
void CameraServerImpl::unsubscribe_storage_information(
×
579
    CameraServer::StorageInformationHandle handle)
580
{
581
    _storage_information_callbacks.unsubscribe(handle);
×
582
}
×
583

584
CameraServer::Result CameraServerImpl::respond_storage_information(
1✔
585
    CameraServer::CameraFeedback storage_information_feedback,
586
    CameraServer::StorageInformation storage_information)
587
{
588
    switch (storage_information_feedback) {
1✔
589
        default:
×
590
            // Fallthrough
591
        case CameraServer::CameraFeedback::Unknown:
592
            return CameraServer::Result::Error;
×
593
        case CameraServer::CameraFeedback::Ok: {
1✔
594
            auto command_ack = _server_component_impl->make_command_ack_message(
1✔
595
                _last_storage_information_command, MAV_RESULT_ACCEPTED);
1✔
596
            _server_component_impl->send_command_ack(command_ack);
1✔
597
            // break and send storage information
598
            break;
1✔
599
        }
600
        case CameraServer::CameraFeedback::Busy: {
×
601
            auto command_ack = _server_component_impl->make_command_ack_message(
×
602
                _last_storage_information_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
603
            _server_component_impl->send_command_ack(command_ack);
×
604
            return CameraServer::Result::Success;
×
605
        }
606
        case CameraServer::CameraFeedback::Failed: {
×
607
            auto command_ack = _server_component_impl->make_command_ack_message(
×
608
                _last_storage_information_command, MAV_RESULT_FAILED);
×
609
            _server_component_impl->send_command_ack(command_ack);
×
610
            return CameraServer::Result::Success;
×
611
        }
612
    }
613

614
    const uint8_t storage_count = 1;
1✔
615

616
    const float total_capacity = storage_information.total_storage_mib;
1✔
617
    const float used_capacity = storage_information.used_storage_mib;
1✔
618
    const float available_capacity = storage_information.available_storage_mib;
1✔
619
    const float read_speed = storage_information.read_speed_mib_s;
1✔
620
    const float write_speed = storage_information.write_speed_mib_s;
1✔
621

622
    auto status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
1✔
623
    switch (storage_information.storage_status) {
1✔
624
        case CameraServer::StorageInformation::StorageStatus::NotAvailable:
×
625
            status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
626
            break;
×
627
        case CameraServer::StorageInformation::StorageStatus::Unformatted:
×
628
            status = STORAGE_STATUS::STORAGE_STATUS_UNFORMATTED;
×
629
            break;
×
630
        case CameraServer::StorageInformation::StorageStatus::Formatted:
1✔
631
            status = STORAGE_STATUS::STORAGE_STATUS_READY;
1✔
632
            break;
1✔
633
        case CameraServer::StorageInformation::StorageStatus::NotSupported:
×
634
            status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
635
            break;
×
636
    }
637

638
    auto type = STORAGE_TYPE::STORAGE_TYPE_UNKNOWN;
1✔
639
    switch (storage_information.storage_type) {
1✔
640
        case CameraServer::StorageInformation::StorageType::UsbStick:
×
641
            type = STORAGE_TYPE::STORAGE_TYPE_USB_STICK;
×
642
            break;
×
643
        case CameraServer::StorageInformation::StorageType::Sd:
×
644
            type = STORAGE_TYPE::STORAGE_TYPE_SD;
×
645
            break;
×
646
        case CameraServer::StorageInformation::StorageType::Microsd:
×
647
            type = STORAGE_TYPE::STORAGE_TYPE_MICROSD;
×
648
            break;
×
649
        case CameraServer::StorageInformation::StorageType::Hd:
×
650
            type = STORAGE_TYPE::STORAGE_TYPE_HD;
×
651
            break;
×
652
        case CameraServer::StorageInformation::StorageType::Other:
×
653
            type = STORAGE_TYPE::STORAGE_TYPE_OTHER;
×
654
            break;
×
655
        default:
1✔
656
            break;
1✔
657
    }
658

659
    std::string name("");
2✔
660
    // This needs to be long enough, otherwise the memcpy in mavlink overflows.
661
    name.resize(32);
1✔
662
    const uint8_t storage_usage = 0;
1✔
663

664
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
1✔
665
        mavlink_message_t message{};
1✔
666
        mavlink_msg_storage_information_pack_chan(
2✔
667
            mavlink_address.system_id,
1✔
668
            mavlink_address.component_id,
1✔
669
            channel,
670
            &message,
671
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
1✔
672
            _last_storage_id,
1✔
673
            storage_count,
674
            status,
1✔
675
            total_capacity,
1✔
676
            used_capacity,
1✔
677
            available_capacity,
1✔
678
            read_speed,
1✔
679
            write_speed,
1✔
680
            type,
1✔
681
            name.data(),
1✔
682
            storage_usage);
683
        return message;
1✔
684
    });
685

686
    return CameraServer::Result::Success;
1✔
687
}
688

689
CameraServer::CaptureStatusHandle
690
CameraServerImpl::subscribe_capture_status(const CameraServer::CaptureStatusCallback& callback)
×
691
{
692
    return _capture_status_callbacks.subscribe(callback);
×
693
}
694

695
void CameraServerImpl::unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle)
×
696
{
697
    _capture_status_callbacks.unsubscribe(handle);
×
698
}
×
699

700
CameraServer::Result CameraServerImpl::respond_capture_status(
×
701
    CameraServer::CameraFeedback capture_status_feedback,
702
    CameraServer::CaptureStatus capture_status)
703
{
704
    switch (capture_status_feedback) {
×
705
        default:
×
706
            // Fallthrough
707
        case CameraServer::CameraFeedback::Unknown:
708
            return CameraServer::Result::Error;
×
709
        case CameraServer::CameraFeedback::Ok: {
×
710
            auto command_ack = _server_component_impl->make_command_ack_message(
×
711
                _last_capture_status_command, MAV_RESULT_ACCEPTED);
×
712
            _server_component_impl->send_command_ack(command_ack);
×
713
            // break and send capture status
714
            break;
×
715
        }
716
        case CameraServer::CameraFeedback::Busy: {
×
717
            auto command_ack = _server_component_impl->make_command_ack_message(
×
718
                _last_capture_status_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
719
            _server_component_impl->send_command_ack(command_ack);
×
720
            return CameraServer::Result::Success;
×
721
        }
722
        case CameraServer::CameraFeedback::Failed: {
×
723
            auto command_ack = _server_component_impl->make_command_ack_message(
×
724
                _last_capture_status_command, MAV_RESULT_FAILED);
×
725
            _server_component_impl->send_command_ack(command_ack);
×
726
            return CameraServer::Result::Success;
×
727
        }
728
    }
729

730
    _capture_status = capture_status;
×
731

732
    send_capture_status();
×
733

734
    return CameraServer::Result::Success;
×
735
}
736

737
CameraServer::FormatStorageHandle
738
CameraServerImpl::subscribe_format_storage(const CameraServer::FormatStorageCallback& callback)
1✔
739
{
740
    return _format_storage_callbacks.subscribe(callback);
1✔
741
}
742
void CameraServerImpl::unsubscribe_format_storage(CameraServer::FormatStorageHandle handle)
×
743
{
744
    _format_storage_callbacks.unsubscribe(handle);
×
745
}
×
746

747
CameraServer::Result
748
CameraServerImpl::respond_format_storage(CameraServer::CameraFeedback format_storage_feedback)
1✔
749
{
750
    switch (format_storage_feedback) {
1✔
751
        default:
×
752
            // Fallthrough
753
        case CameraServer::CameraFeedback::Unknown:
754
            return CameraServer::Result::Error;
×
755
        case CameraServer::CameraFeedback::Ok: {
1✔
756
            auto command_ack = _server_component_impl->make_command_ack_message(
1✔
757
                _last_format_storage_command, MAV_RESULT_ACCEPTED);
1✔
758
            _server_component_impl->send_command_ack(command_ack);
1✔
759
            return CameraServer::Result::Success;
1✔
760
        }
761
        case CameraServer::CameraFeedback::Busy: {
×
762
            auto command_ack = _server_component_impl->make_command_ack_message(
×
763
                _last_format_storage_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
764
            _server_component_impl->send_command_ack(command_ack);
×
765
            return CameraServer::Result::Success;
×
766
        }
767
        case CameraServer::CameraFeedback::Failed: {
×
768
            auto command_ack = _server_component_impl->make_command_ack_message(
×
769
                _last_format_storage_command, MAV_RESULT_FAILED);
×
770
            _server_component_impl->send_command_ack(command_ack);
×
771
            return CameraServer::Result::Success;
×
772
        }
773
    }
774
}
775

776
CameraServer::ResetSettingsHandle
777
CameraServerImpl::subscribe_reset_settings(const CameraServer::ResetSettingsCallback& callback)
1✔
778
{
779
    return _reset_settings_callbacks.subscribe(callback);
1✔
780
}
781

782
void CameraServerImpl::unsubscribe_reset_settings(CameraServer::ResetSettingsHandle handle)
×
783
{
784
    _reset_settings_callbacks.unsubscribe(handle);
×
785
}
×
786

787
CameraServer::Result
788
CameraServerImpl::respond_reset_settings(CameraServer::CameraFeedback reset_settings_feedback)
1✔
789
{
790
    switch (reset_settings_feedback) {
1✔
791
        default:
×
792
            // Fallthrough
793
        case CameraServer::CameraFeedback::Unknown:
794
            return CameraServer::Result::Error;
×
795
        case CameraServer::CameraFeedback::Ok: {
1✔
796
            auto command_ack = _server_component_impl->make_command_ack_message(
1✔
797
                _last_reset_settings_command, MAV_RESULT_ACCEPTED);
1✔
798
            _server_component_impl->send_command_ack(command_ack);
1✔
799
            return CameraServer::Result::Success;
1✔
800
        }
801
        case CameraServer::CameraFeedback::Busy: {
×
802
            auto command_ack = _server_component_impl->make_command_ack_message(
×
803
                _last_reset_settings_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
804
            _server_component_impl->send_command_ack(command_ack);
×
805
            return CameraServer::Result::Success;
×
806
        }
807
        case CameraServer::CameraFeedback::Failed: {
×
808
            auto command_ack = _server_component_impl->make_command_ack_message(
×
809
                _last_reset_settings_command, MAV_RESULT_FAILED);
×
810
            _server_component_impl->send_command_ack(command_ack);
×
811
            return CameraServer::Result::Success;
×
812
        }
813
    }
814
}
815

816
CameraServer::TrackingPointCommandHandle CameraServerImpl::subscribe_tracking_point_command(
×
817
    const CameraServer::TrackingPointCommandCallback& callback)
818
{
819
    return _tracking_point_callbacks.subscribe(callback);
×
820
}
821

822
void CameraServerImpl::unsubscribe_tracking_point_command(
×
823
    CameraServer::TrackingPointCommandHandle handle)
824
{
825
    _tracking_point_callbacks.unsubscribe(handle);
×
826
}
×
827

828
CameraServer::Result CameraServerImpl::respond_tracking_point_command(
×
829
    CameraServer::CameraFeedback tracking_point_feedback)
830
{
831
    switch (tracking_point_feedback) {
×
832
        default:
×
833
            // Fallthrough
834
        case CameraServer::CameraFeedback::Unknown:
835
            return CameraServer::Result::Error;
×
836
        case CameraServer::CameraFeedback::Ok: {
×
837
            auto command_ack = _server_component_impl->make_command_ack_message(
×
838
                _last_track_point_command, MAV_RESULT_ACCEPTED);
×
839
            _server_component_impl->send_command_ack(command_ack);
×
840
            break;
×
841
        }
842
        case CameraServer::CameraFeedback::Busy: {
×
843
            auto command_ack = _server_component_impl->make_command_ack_message(
×
844
                _last_track_point_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
845
            _server_component_impl->send_command_ack(command_ack);
×
846
            return CameraServer::Result::Success;
×
847
        }
848
        case CameraServer::CameraFeedback::Failed: {
×
849
            auto command_ack = _server_component_impl->make_command_ack_message(
×
850
                _last_track_point_command, MAV_RESULT_FAILED);
×
851
            _server_component_impl->send_command_ack(command_ack);
×
852
            return CameraServer::Result::Success;
×
853
        }
854
    }
855
    return CameraServer::Result::Success;
×
856
}
857

858
CameraServer::TrackingRectangleCommandHandle CameraServerImpl::subscribe_tracking_rectangle_command(
×
859
    const CameraServer::TrackingRectangleCommandCallback& callback)
860
{
861
    return _tracking_rectangle_callbacks.subscribe(callback);
×
862
}
863

864
void CameraServerImpl::unsubscribe_tracking_rectangle_command(
×
865
    CameraServer::TrackingRectangleCommandHandle handle)
866
{
867
    _tracking_rectangle_callbacks.unsubscribe(handle);
×
868
}
×
869

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

900
CameraServer::TrackingOffCommandHandle CameraServerImpl::subscribe_tracking_off_command(
×
901
    const CameraServer::TrackingOffCommandCallback& callback)
902
{
903
    return _tracking_off_callbacks.subscribe(callback);
×
904
}
905

906
void CameraServerImpl::unsubscribe_tracking_off_command(
×
907
    CameraServer::TrackingOffCommandHandle handle)
908
{
909
    _tracking_off_callbacks.unsubscribe(handle);
×
910
}
×
911

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

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

947
    _last_interval_index = index;
1✔
948

949
    _image_capture_timer_cookie = _server_component_impl->add_call_every(
1✔
950
        [this, remaining]() {
9✔
951
            LogDebug() << "capture image timer triggered";
3✔
952

953
            if (!_take_photo_callbacks.empty()) {
3✔
954
                _take_photo_callbacks(_last_interval_index++);
3✔
955
                (*remaining)--;
3✔
956
            }
957

958
            if (*remaining == 0) {
3✔
959
                stop_image_capture_interval();
×
960
            }
961
        },
3✔
962
        interval_s);
963

964
    _is_image_capture_interval_set = true;
1✔
965
    _image_capture_timer_interval_s = interval_s;
1✔
966
}
1✔
967

968
void CameraServerImpl::stop_image_capture_interval()
12✔
969
{
970
    _server_component_impl->remove_call_every(_image_capture_timer_cookie);
12✔
971

972
    _is_image_capture_interval_set = false;
12✔
973
    _image_capture_timer_interval_s = 0;
12✔
974
}
12✔
975

976
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_information_request(
×
977
    const MavlinkCommandReceiver::CommandLong& command)
978
{
979
    LogDebug() << "Camera info request";
×
980

981
    if (static_cast<int>(command.params.param1) == 0) {
×
982
        return _server_component_impl->make_command_ack_message(
×
983
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
984
    }
985

986
    return send_camera_information(command);
×
987
}
988

989
std::optional<mavlink_command_ack_t>
990
CameraServerImpl::process_request_message(const MavlinkCommandReceiver::CommandLong& command)
40✔
991
{
992
    switch (static_cast<int>(command.params.param1)) {
40✔
993
        case MAVLINK_MSG_ID_CAMERA_INFORMATION:
9✔
994
            return send_camera_information(command);
9✔
995

996
        case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS:
5✔
997
            send_capture_status();
5✔
998
            return _server_component_impl->make_command_ack_message(
10✔
999
                command, MAV_RESULT::MAV_RESULT_ACCEPTED);
10✔
1000

1001
        default:
26✔
1002
            LogWarn() << "Got unknown request message!";
26✔
1003
            return _server_component_impl->make_command_ack_message(
52✔
1004
                command, MAV_RESULT::MAV_RESULT_DENIED);
52✔
1005
    }
1006
}
1007

1008
std::optional<mavlink_command_ack_t>
1009
CameraServerImpl::send_camera_information(const MavlinkCommandReceiver::CommandLong& command)
9✔
1010
{
1011
    if (!_is_information_set) {
9✔
1012
        return _server_component_impl->make_command_ack_message(
×
1013
            command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED);
×
1014
    }
1015

1016
    // ack needs to be sent before camera information message
1017
    auto command_ack =
9✔
1018
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
9✔
1019
    _server_component_impl->send_command_ack(command_ack);
9✔
1020

1021
    // It is safe to ignore the return value of parse_version_string() here
1022
    // since the string was already validated in set_information().
1023
    uint32_t firmware_version;
9✔
1024
    parse_version_string(_information.firmware_version, firmware_version);
9✔
1025

1026
    // capability flags are determined by subscriptions
1027
    uint32_t capability_flags{};
9✔
1028

1029
    if (!_take_photo_callbacks.empty()) {
9✔
1030
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE;
2✔
1031
    }
1032

1033
    if (!_start_video_callbacks.empty()) {
9✔
1034
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
×
1035
    }
1036

1037
    if (!_set_mode_callbacks.empty()) {
9✔
1038
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES;
2✔
1039
    }
1040

1041
    if (_information.image_in_video_mode_supported) {
9✔
1042
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE;
×
1043
    }
1044

1045
    if (_information.video_in_image_mode_supported) {
9✔
1046
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE;
×
1047
    }
1048

1049
    if (_is_video_streaming_set) {
9✔
1050
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM;
1✔
1051
    }
1052

1053
    if (!_tracking_point_callbacks.empty()) {
9✔
1054
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT;
×
1055
    }
1056

1057
    if (!_tracking_rectangle_callbacks.empty()) {
9✔
1058
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE;
×
1059
    }
1060

1061
    if (!_zoom_range_callbacks.empty() || !_zoom_in_start_callbacks.empty() ||
18✔
1062
        !_zoom_out_start_callbacks.empty()) {
9✔
1063
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM;
×
1064
    }
1065

1066
    _information.vendor_name.resize(sizeof(mavlink_camera_information_t::vendor_name));
9✔
1067
    _information.model_name.resize(sizeof(mavlink_camera_information_t::model_name));
9✔
1068
    _information.definition_file_uri.resize(
9✔
1069
        sizeof(mavlink_camera_information_t::cam_definition_uri));
1070

1071
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
9✔
1072
        mavlink_message_t message{};
9✔
1073
        mavlink_msg_camera_information_pack_chan(
27✔
1074
            mavlink_address.system_id,
9✔
1075
            mavlink_address.component_id,
9✔
1076
            channel,
1077
            &message,
1078
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
18✔
1079
            reinterpret_cast<const uint8_t*>(_information.vendor_name.c_str()),
9✔
1080
            reinterpret_cast<const uint8_t*>(_information.model_name.c_str()),
9✔
1081
            firmware_version,
9✔
1082
            _information.focal_length_mm,
1083
            _information.horizontal_sensor_size_mm,
1084
            _information.vertical_sensor_size_mm,
1085
            _information.horizontal_resolution_px,
9✔
1086
            _information.vertical_resolution_px,
9✔
1087
            _information.lens_id,
9✔
1088
            capability_flags,
9✔
1089
            _information.definition_file_version,
9✔
1090
            _information.definition_file_uri.c_str(),
1091
            0,
1092
            0);
1093
        return message;
9✔
1094
    });
1095

1096
    return std::nullopt;
9✔
1097
}
1098

1099
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_settings_request(
5✔
1100
    const MavlinkCommandReceiver::CommandLong& command)
1101
{
1102
    auto settings = static_cast<bool>(command.params.param1);
5✔
1103

1104
    if (!settings) {
5✔
1105
        return _server_component_impl->make_command_ack_message(
×
1106
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1107
    }
1108

1109
    // ack needs to be sent before camera information message
1110
    auto command_ack =
5✔
1111
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
5✔
1112
    _server_component_impl->send_command_ack(command_ack);
5✔
1113
    LogDebug() << "sent settings ack";
5✔
1114

1115
    // unsupported
1116
    const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE;
5✔
1117
    const float zoom_level = 0;
5✔
1118
    const float focus_level = 0;
5✔
1119

1120
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
5✔
1121
        mavlink_message_t message{};
5✔
1122
        mavlink_msg_camera_settings_pack_chan(
10✔
1123
            mavlink_address.system_id,
5✔
1124
            mavlink_address.component_id,
5✔
1125
            channel,
1126
            &message,
1127
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
5✔
1128
            mode_id,
1129
            zoom_level,
5✔
1130
            focus_level,
5✔
1131
            0);
1132
        return message;
5✔
1133
    });
1134
    LogDebug() << "sent settings msg";
5✔
1135

1136
    // ack was already sent
1137
    return std::nullopt;
5✔
1138
}
1139

1140
std::optional<mavlink_command_ack_t> CameraServerImpl::process_storage_information_request(
9✔
1141
    const MavlinkCommandReceiver::CommandLong& command)
1142
{
1143
    auto storage_id = static_cast<uint8_t>(command.params.param1);
9✔
1144
    auto information = static_cast<bool>(command.params.param2);
9✔
1145

1146
    if (!information) {
9✔
1147
        return _server_component_impl->make_command_ack_message(
×
1148
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1149
    }
1150

1151
    if (_storage_information_callbacks.empty()) {
9✔
1152
        LogDebug()
16✔
1153
            << "Get storage information requested with no set storage information subscriber";
16✔
1154
        return _server_component_impl->make_command_ack_message(
16✔
1155
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
16✔
1156
    }
1157

1158
    // TODO may need support multi storage id
1159
    _last_storage_id = storage_id;
1✔
1160

1161
    _last_storage_information_command = command;
1✔
1162
    _storage_information_callbacks(storage_id);
1✔
1163

1164
    // ack will be sent later in respond_storage_information
1165
    return std::nullopt;
1✔
1166
}
1167

1168
std::optional<mavlink_command_ack_t>
1169
CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLong& command)
1✔
1170
{
1171
    auto storage_id = static_cast<uint8_t>(command.params.param1);
1✔
1172
    auto format = static_cast<bool>(command.params.param2);
1✔
1173
    auto reset_image_log = static_cast<bool>(command.params.param3);
1✔
1174

1175
    UNUSED(format);
1✔
1176
    UNUSED(reset_image_log);
1✔
1177
    if (_format_storage_callbacks.empty()) {
1✔
1178
        LogDebug() << "process storage format requested with no storage format subscriber";
×
1179
        return _server_component_impl->make_command_ack_message(
×
1180
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1181
    }
1182

1183
    _last_format_storage_command = command;
1✔
1184
    _format_storage_callbacks(storage_id);
1✔
1185

1186
    return std::nullopt;
1✔
1187
}
1188

1189
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_capture_status_request(
×
1190
    const MavlinkCommandReceiver::CommandLong& command)
1191
{
1192
    auto capture_status = static_cast<bool>(command.params.param1);
×
1193

1194
    if (!capture_status) {
×
1195
        return _server_component_impl->make_command_ack_message(
×
1196
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1197
    }
1198

1199
    if (_capture_status_callbacks.empty()) {
×
1200
        LogDebug() << "process camera capture status requested with no capture status subscriber";
×
1201
        return _server_component_impl->make_command_ack_message(
×
1202
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1203
    }
1204

1205
    _last_capture_status_command = command;
×
1206

1207
    // may not need param for now ,just use zero
1208
    _capture_status_callbacks(0);
×
1209

1210
    // ack was already sent
1211
    return std::nullopt;
×
1212
}
1213

1214
void CameraServerImpl::send_capture_status()
5✔
1215
{
1216
    uint8_t image_status{};
5✔
1217
    if (_capture_status.image_status ==
5✔
1218
            CameraServer::CaptureStatus::ImageStatus::CaptureInProgress ||
5✔
1219
        _capture_status.image_status ==
5✔
1220
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress) {
1221
        image_status |= StatusFlags::IN_PROGRESS;
×
1222
    }
1223

1224
    if (_capture_status.image_status == CameraServer::CaptureStatus::ImageStatus::IntervalIdle ||
5✔
1225
        _capture_status.image_status ==
5✔
1226
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress ||
5✔
1227
        _is_image_capture_interval_set) {
5✔
1228
        image_status |= StatusFlags::INTERVAL_SET;
×
1229
    }
1230

1231
    uint8_t video_status = 0;
5✔
1232
    if (_capture_status.video_status == CameraServer::CaptureStatus::VideoStatus::Idle) {
5✔
1233
        video_status = 0;
5✔
1234
    } else if (
×
1235
        _capture_status.video_status ==
×
1236
        CameraServer::CaptureStatus::VideoStatus::CaptureInProgress) {
1237
        video_status = 1;
×
1238
    }
1239

1240
    const uint32_t recording_time_ms =
5✔
1241
        static_cast<uint32_t>(static_cast<double>(_capture_status.recording_time_s) * 1e3);
5✔
1242
    const float available_capacity = _capture_status.available_capacity_mib;
5✔
1243

1244
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
5✔
1245
        mavlink_message_t message{};
5✔
1246
        mavlink_msg_camera_capture_status_pack_chan(
10✔
1247
            mavlink_address.system_id,
5✔
1248
            mavlink_address.component_id,
5✔
1249
            channel,
1250
            &message,
1251
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
5✔
1252
            image_status,
5✔
1253
            video_status,
5✔
1254
            _image_capture_timer_interval_s,
1255
            recording_time_ms,
5✔
1256
            available_capacity,
5✔
1257
            _image_capture_count,
1258
            0);
1259
        return message;
5✔
1260
    });
1261
}
5✔
1262

1263
std::optional<mavlink_command_ack_t>
1264
CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::CommandLong& command)
1✔
1265
{
1266
    auto reset = static_cast<bool>(command.params.param1);
1✔
1267

1268
    UNUSED(reset);
1✔
1269

1270
    if (_reset_settings_callbacks.empty()) {
1✔
1271
        LogDebug() << "reset camera settings requested with no camera settings subscriber";
×
1272
        return _server_component_impl->make_command_ack_message(
×
1273
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1274
    }
1275

1276
    _last_reset_settings_command = command;
1✔
1277
    _reset_settings_callbacks(0);
1✔
1278

1279
    return std::nullopt;
1✔
1280
}
1281

1282
std::optional<mavlink_command_ack_t>
1283
CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandLong& command)
2✔
1284
{
1285
    auto camera_mode = static_cast<CAMERA_MODE>(command.params.param2);
2✔
1286

1287
    if (_set_mode_callbacks.empty()) {
2✔
1288
        LogDebug() << "Set mode requested with no set mode subscriber";
×
1289
        return _server_component_impl->make_command_ack_message(
×
1290
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1291
    }
1292

1293
    // convert camera mode enum type
1294
    CameraServer::Mode convert_camera_mode = CameraServer::Mode::Unknown;
2✔
1295
    if (camera_mode == CAMERA_MODE_IMAGE) {
2✔
1296
        convert_camera_mode = CameraServer::Mode::Photo;
1✔
1297
    } else if (camera_mode == CAMERA_MODE_VIDEO) {
1✔
1298
        convert_camera_mode = CameraServer::Mode::Video;
1✔
1299
    }
1300

1301
    if (convert_camera_mode == CameraServer::Mode::Unknown) {
2✔
1302
        return _server_component_impl->make_command_ack_message(
×
1303
            command, MAV_RESULT::MAV_RESULT_DENIED);
×
1304
    }
1305

1306
    _last_set_mode_command = command;
2✔
1307
    _set_mode_callbacks(convert_camera_mode);
2✔
1308

1309
    return std::nullopt;
2✔
1310
}
1311

1312
std::optional<mavlink_command_ack_t>
1313
CameraServerImpl::process_set_camera_zoom(const MavlinkCommandReceiver::CommandLong& command)
×
1314
{
1315
    auto zoom_type = static_cast<CAMERA_ZOOM_TYPE>(command.params.param1);
×
1316
    auto zoom_value = command.params.param2;
×
1317

1318
    if (_zoom_in_start_callbacks.empty() && _zoom_out_start_callbacks.empty() &&
×
1319
        _zoom_stop_callbacks.empty() && _zoom_range_callbacks.empty()) {
×
1320
        LogWarn() << "No camera zoom is supported";
×
1321
        return _server_component_impl->make_command_ack_message(
×
1322
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1323
    }
1324

1325
    auto unsupported = [&]() {
×
1326
        LogWarn() << "unsupported set camera zoom type (" << (int)zoom_type << ") request";
×
1327
    };
×
1328

1329
    switch (zoom_type) {
×
1330
        case ZOOM_TYPE_CONTINUOUS:
×
1331
            if (zoom_value == -1.f) {
×
1332
                if (_zoom_out_start_callbacks.empty()) {
×
1333
                    unsupported();
×
1334
                    return _server_component_impl->make_command_ack_message(
×
1335
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1336
                } else {
1337
                    _last_zoom_out_start_command = command;
×
1338
                    int dummy = 0;
×
1339
                    _zoom_out_start_callbacks(dummy);
×
1340
                }
1341
            } else if (zoom_value == 1.f) {
×
1342
                if (_zoom_in_start_callbacks.empty()) {
×
1343
                    unsupported();
×
1344
                    return _server_component_impl->make_command_ack_message(
×
1345
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1346
                } else {
1347
                    _last_zoom_in_start_command = command;
×
1348
                    int dummy = 0;
×
1349
                    _zoom_in_start_callbacks(dummy);
×
1350
                }
1351
            } else if (zoom_value == 0.f) {
×
1352
                if (_zoom_stop_callbacks.empty()) {
×
1353
                    unsupported();
×
1354
                    return _server_component_impl->make_command_ack_message(
×
1355
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1356
                } else {
1357
                    _last_zoom_stop_command = command;
×
1358
                    int dummy = 0;
×
1359
                    _zoom_stop_callbacks(dummy);
×
1360
                }
1361
            } else {
1362
                LogWarn() << "Invalid zoom value";
×
1363
                return _server_component_impl->make_command_ack_message(
×
1364
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1365
            }
1366
            break;
×
1367
        case ZOOM_TYPE_RANGE:
×
1368
            if (_zoom_range_callbacks.empty()) {
×
1369
                unsupported();
×
1370
                return _server_component_impl->make_command_ack_message(
×
1371
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1372

1373
            } else {
1374
                _last_zoom_range_command = command;
×
1375
                _zoom_range_callbacks(zoom_value);
×
1376
            }
1377
            break;
×
1378
        case ZOOM_TYPE_STEP:
×
1379
        // Fallthrough
1380
        case ZOOM_TYPE_FOCAL_LENGTH:
1381
        // Fallthrough
1382
        case ZOOM_TYPE_HORIZONTAL_FOV:
1383
        // Fallthrough
1384
        default:
1385
            unsupported();
×
1386
            return _server_component_impl->make_command_ack_message(
×
1387
                command, MAV_RESULT::MAV_RESULT_DENIED);
×
1388
            break;
1389
    }
1390

1391
    // For any success so far, we don't ack yet, but later when the respond function is called.
1392
    return std::nullopt;
×
1393
}
1394

1395
std::optional<mavlink_command_ack_t>
1396
CameraServerImpl::process_set_camera_focus(const MavlinkCommandReceiver::CommandLong& command)
×
1397
{
1398
    auto focus_type = static_cast<SET_FOCUS_TYPE>(command.params.param1);
×
1399
    auto focus_value = command.params.param2;
×
1400

1401
    UNUSED(focus_type);
×
1402
    UNUSED(focus_value);
×
1403

1404
    LogDebug() << "unsupported set camera focus request";
×
1405

1406
    return _server_component_impl->make_command_ack_message(
×
1407
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1408
}
1409

1410
std::optional<mavlink_command_ack_t>
1411
CameraServerImpl::process_set_storage_usage(const MavlinkCommandReceiver::CommandLong& command)
×
1412
{
1413
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
1414
    auto usage = static_cast<STORAGE_USAGE_FLAG>(command.params.param2);
×
1415

1416
    UNUSED(storage_id);
×
1417
    UNUSED(usage);
×
1418

1419
    LogDebug() << "unsupported set storage usage request";
×
1420

1421
    return _server_component_impl->make_command_ack_message(
×
1422
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1423
}
1424

1425
std::optional<mavlink_command_ack_t>
1426
CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command)
2✔
1427
{
1428
    auto interval_s = command.params.param2;
2✔
1429
    auto total_images = static_cast<int32_t>(command.params.param3);
2✔
1430
    auto seq_number = static_cast<int32_t>(command.params.param4);
2✔
1431

1432
    LogDebug() << "received image start capture request - interval: " << +interval_s
6✔
1433
               << " total: " << +total_images << " index: " << +seq_number;
6✔
1434

1435
    // TODO: validate parameters and return MAV_RESULT_DENIED not valid
1436

1437
    stop_image_capture_interval();
2✔
1438

1439
    if (_take_photo_callbacks.empty()) {
2✔
1440
        LogDebug() << "image capture requested with no take photo subscriber";
×
1441
        return _server_component_impl->make_command_ack_message(
×
1442
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1443
    }
1444

1445
    // single image capture
1446
    if (total_images == 1) {
2✔
1447
        // MAV_RESULT_ACCEPTED must be sent before CAMERA_IMAGE_CAPTURED
1448
        auto command_ack = _server_component_impl->make_command_ack_message(
1✔
1449
            command, MAV_RESULT::MAV_RESULT_IN_PROGRESS);
1450
        _server_component_impl->send_command_ack(command_ack);
1✔
1451

1452
        _last_take_photo_command = command;
1✔
1453

1454
        _take_photo_callbacks(seq_number);
1✔
1455

1456
        return std::nullopt;
1✔
1457
    }
1458

1459
    start_image_capture_interval(interval_s, total_images, seq_number);
1✔
1460

1461
    return _server_component_impl->make_command_ack_message(
2✔
1462
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
2✔
1463
}
1464

1465
std::optional<mavlink_command_ack_t>
1466
CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
1✔
1467
{
1468
    LogDebug() << "received image stop capture request";
1✔
1469

1470
    // REVISIT: should we return something other that MAV_RESULT_ACCEPTED if
1471
    // there is not currently a capture interval active?
1472
    stop_image_capture_interval();
1✔
1473

1474
    return _server_component_impl->make_command_ack_message(
2✔
1475
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
2✔
1476
}
1477

1478
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_image_capture_request(
×
1479
    const MavlinkCommandReceiver::CommandLong& command)
1480
{
1481
    auto seq_number = static_cast<uint32_t>(command.params.param1);
×
1482

1483
    UNUSED(seq_number);
×
1484

1485
    LogDebug() << "unsupported image capture request";
×
1486

1487
    return _server_component_impl->make_command_ack_message(
×
1488
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1489
}
1490

1491
std::optional<mavlink_command_ack_t>
1492
CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1493
{
1494
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1495
    auto status_frequency = command.params.param2;
×
1496

1497
    UNUSED(status_frequency);
×
1498

1499
    if (_start_video_callbacks.empty()) {
×
1500
        LogDebug() << "video start capture requested with no video start capture subscriber";
×
1501
        return _server_component_impl->make_command_ack_message(
×
1502
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1503
    }
1504

1505
    _last_start_video_command = command;
×
1506
    _start_video_callbacks(stream_id);
×
1507

1508
    return std::nullopt;
×
1509
}
1510

1511
std::optional<mavlink_command_ack_t>
1512
CameraServerImpl::process_video_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1513
{
1514
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1515

1516
    if (_stop_video_callbacks.empty()) {
×
1517
        LogDebug() << "video stop capture requested with no video stop capture subscriber";
×
1518
        return _server_component_impl->make_command_ack_message(
×
1519
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1520
    }
1521

1522
    _last_stop_video_command = command;
×
1523
    _stop_video_callbacks(stream_id);
×
1524

1525
    return std::nullopt;
×
1526
}
1527

1528
std::optional<mavlink_command_ack_t>
1529
CameraServerImpl::process_video_start_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1530
{
1531
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1532

1533
    if (_start_video_streaming_callbacks.empty()) {
×
1534
        LogDebug() << "video start streaming requested with no video start streaming subscriber";
×
1535
        return _server_component_impl->make_command_ack_message(
×
1536
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1537
    }
1538

1539
    _last_start_video_streaming_command = command;
×
1540
    _start_video_streaming_callbacks(stream_id);
×
1541

1542
    return std::nullopt;
×
1543
}
1544

1545
std::optional<mavlink_command_ack_t>
1546
CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1547
{
1548
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1549

1550
    if (_stop_video_streaming_callbacks.empty()) {
×
1551
        LogDebug() << "video stop streaming requested with no video stop streaming subscriber";
×
1552
        return _server_component_impl->make_command_ack_message(
×
1553
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1554
    }
1555

1556
    _last_stop_video_streaming_command = command;
×
1557
    _stop_video_streaming_callbacks(stream_id);
×
1558

1559
    return std::nullopt;
×
1560
}
1561

1562
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_information_request(
1✔
1563
    const MavlinkCommandReceiver::CommandLong& command)
1564
{
1565
    auto stream_id = static_cast<uint8_t>(command.params.param1);
1✔
1566

1567
    UNUSED(stream_id);
1✔
1568

1569
    if (_is_video_streaming_set) {
1✔
1570
        auto command_ack = _server_component_impl->make_command_ack_message(
1✔
1571
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
1572
        _server_component_impl->send_command_ack(command_ack);
1✔
1573
        LogDebug() << "sent video streaming ack";
1✔
1574

1575
        const char name[32] = "";
1✔
1576

1577
        _video_streaming.rtsp_uri.resize(sizeof(mavlink_video_stream_information_t::uri));
1✔
1578

1579
        mavlink_message_t msg{};
1✔
1580
        mavlink_msg_video_stream_information_pack(
2✔
1581
            _server_component_impl->get_own_system_id(),
1✔
1582
            _server_component_impl->get_own_component_id(),
1✔
1583
            &msg,
1584
            0, // Stream id
1585
            0, // Count
1586
            VIDEO_STREAM_TYPE_RTSP,
1587
            VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1588
            0, // famerate
1589
            0, // resolution horizontal
1590
            0, // resolution vertical
1591
            0, // bitrate
1592
            0, // rotation
1593
            0, // horizontal field of view
1594
            name,
1595
            _video_streaming.rtsp_uri.c_str(),
1596
            0,
1597
            0);
1598

1599
        _server_component_impl->send_message(msg);
1✔
1600

1601
        // Ack already sent.
1602
        return std::nullopt;
1✔
1603

1604
    } else {
1605
        return _server_component_impl->make_command_ack_message(
×
1606
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1607
    }
1608
}
1609

1610
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_status_request(
6✔
1611
    const MavlinkCommandReceiver::CommandLong& command)
1612
{
1613
    auto stream_id = static_cast<uint8_t>(command.params.param1);
6✔
1614

1615
    UNUSED(stream_id);
6✔
1616

1617
    if (!_is_video_streaming_set) {
6✔
1618
        return _server_component_impl->make_command_ack_message(
4✔
1619
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
4✔
1620
    }
1621

1622
    auto command_ack =
4✔
1623
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
4✔
1624
    _server_component_impl->send_command_ack(command_ack);
4✔
1625
    LogDebug() << "sent video streaming ack";
4✔
1626

1627
    mavlink_message_t msg{};
4✔
1628
    mavlink_msg_video_stream_status_pack(
4✔
1629
        _server_component_impl->get_own_system_id(),
4✔
1630
        _server_component_impl->get_own_component_id(),
4✔
1631
        &msg,
1632
        0, // Stream id
1633
        VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1634
        0, // framerate
1635
        0, // resolution horizontal
1636
        0, // resolution vertical
1637
        0, // bitrate
1638
        0, // rotation
1639
        0, // horizontal field of view
1640
        0);
1641
    _server_component_impl->send_message(msg);
4✔
1642

1643
    // ack was already sent
1644
    return std::nullopt;
4✔
1645
}
1646

1647
CameraServer::ZoomInStartHandle
1648
CameraServerImpl::subscribe_zoom_in_start(const CameraServer::ZoomInStartCallback& callback)
×
1649
{
1650
    return _zoom_in_start_callbacks.subscribe(callback);
×
1651
}
1652

1653
void CameraServerImpl::unsubscribe_zoom_in_start(CameraServer::ZoomInStartHandle handle)
×
1654
{
1655
    _zoom_in_start_callbacks.unsubscribe(handle);
×
1656
}
×
1657

1658
CameraServer::Result
1659
CameraServerImpl::respond_zoom_in_start(CameraServer::CameraFeedback zoom_in_start_feedback)
×
1660
{
1661
    switch (zoom_in_start_feedback) {
×
1662
        default:
×
1663
            // Fallthrough
1664
        case CameraServer::CameraFeedback::Unknown:
1665
            return CameraServer::Result::Error;
×
1666
        case CameraServer::CameraFeedback::Ok: {
×
1667
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1668
                _last_zoom_in_start_command, MAV_RESULT_ACCEPTED);
×
1669
            _server_component_impl->send_command_ack(command_ack);
×
1670
            return CameraServer::Result::Success;
×
1671
        }
1672
        case CameraServer::CameraFeedback::Busy: {
×
1673
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1674
                _last_zoom_in_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1675
            _server_component_impl->send_command_ack(command_ack);
×
1676
            return CameraServer::Result::Success;
×
1677
        }
1678
        case CameraServer::CameraFeedback::Failed: {
×
1679
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1680
                _last_zoom_in_start_command, MAV_RESULT_FAILED);
×
1681
            _server_component_impl->send_command_ack(command_ack);
×
1682
            return CameraServer::Result::Success;
×
1683
        }
1684
    }
1685
}
1686

1687
CameraServer::ZoomOutStartHandle
1688
CameraServerImpl::subscribe_zoom_out_start(const CameraServer::ZoomOutStartCallback& callback)
×
1689
{
1690
    return _zoom_out_start_callbacks.subscribe(callback);
×
1691
}
1692

1693
void CameraServerImpl::unsubscribe_zoom_out_start(CameraServer::ZoomOutStartHandle handle)
×
1694
{
1695
    _zoom_out_start_callbacks.unsubscribe(handle);
×
1696
}
×
1697

1698
CameraServer::Result
1699
CameraServerImpl::respond_zoom_out_start(CameraServer::CameraFeedback zoom_out_start_feedback)
×
1700
{
1701
    switch (zoom_out_start_feedback) {
×
1702
        default:
×
1703
            // Fallthrough
1704
        case CameraServer::CameraFeedback::Unknown:
1705
            return CameraServer::Result::Error;
×
1706
        case CameraServer::CameraFeedback::Ok: {
×
1707
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1708
                _last_zoom_out_start_command, MAV_RESULT_ACCEPTED);
×
1709
            _server_component_impl->send_command_ack(command_ack);
×
1710
            return CameraServer::Result::Success;
×
1711
        }
1712
        case CameraServer::CameraFeedback::Busy: {
×
1713
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1714
                _last_zoom_out_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1715
            _server_component_impl->send_command_ack(command_ack);
×
1716
            return CameraServer::Result::Success;
×
1717
        }
1718
        case CameraServer::CameraFeedback::Failed: {
×
1719
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1720
                _last_zoom_out_start_command, MAV_RESULT_FAILED);
×
1721
            _server_component_impl->send_command_ack(command_ack);
×
1722
            return CameraServer::Result::Success;
×
1723
        }
1724
    }
1725
}
1726

1727
CameraServer::ZoomStopHandle
1728
CameraServerImpl::subscribe_zoom_stop(const CameraServer::ZoomStopCallback& callback)
×
1729
{
1730
    return _zoom_stop_callbacks.subscribe(callback);
×
1731
}
1732

1733
void CameraServerImpl::unsubscribe_zoom_stop(CameraServer::ZoomStopHandle handle)
×
1734
{
1735
    _zoom_stop_callbacks.unsubscribe(handle);
×
1736
}
×
1737

1738
CameraServer::Result
1739
CameraServerImpl::respond_zoom_stop(CameraServer::CameraFeedback zoom_stop_feedback)
×
1740
{
1741
    switch (zoom_stop_feedback) {
×
1742
        default:
×
1743
            // Fallthrough
1744
        case CameraServer::CameraFeedback::Unknown:
1745
            return CameraServer::Result::Error;
×
1746
        case CameraServer::CameraFeedback::Ok: {
×
1747
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1748
                _last_zoom_stop_command, MAV_RESULT_ACCEPTED);
×
1749
            _server_component_impl->send_command_ack(command_ack);
×
1750
            return CameraServer::Result::Success;
×
1751
        }
1752
        case CameraServer::CameraFeedback::Busy: {
×
1753
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1754
                _last_zoom_stop_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1755
            _server_component_impl->send_command_ack(command_ack);
×
1756
            return CameraServer::Result::Success;
×
1757
        }
1758
        case CameraServer::CameraFeedback::Failed: {
×
1759
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1760
                _last_zoom_stop_command, MAV_RESULT_FAILED);
×
1761
            _server_component_impl->send_command_ack(command_ack);
×
1762
            return CameraServer::Result::Success;
×
1763
        }
1764
    }
1765
}
1766

1767
CameraServer::ZoomRangeHandle
1768
CameraServerImpl::subscribe_zoom_range(const CameraServer::ZoomRangeCallback& callback)
×
1769
{
1770
    return _zoom_range_callbacks.subscribe(callback);
×
1771
}
1772

1773
void CameraServerImpl::unsubscribe_zoom_range(CameraServer::ZoomRangeHandle handle)
×
1774
{
1775
    _zoom_range_callbacks.unsubscribe(handle);
×
1776
}
×
1777

1778
CameraServer::Result
1779
CameraServerImpl::respond_zoom_range(CameraServer::CameraFeedback zoom_range_feedback)
×
1780
{
1781
    switch (zoom_range_feedback) {
×
1782
        case CameraServer::CameraFeedback::Ok: {
×
1783
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1784
                _last_zoom_range_command, MAV_RESULT_ACCEPTED);
×
1785
            _server_component_impl->send_command_ack(command_ack);
×
1786
            return CameraServer::Result::Success;
×
1787
        }
1788
        case CameraServer::CameraFeedback::Busy: {
×
1789
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1790
                _last_zoom_range_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1791
            _server_component_impl->send_command_ack(command_ack);
×
1792
            return CameraServer::Result::Success;
×
1793
        }
1794
        case CameraServer::CameraFeedback::Failed: {
×
1795
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1796
                _last_zoom_range_command, MAV_RESULT_FAILED);
×
1797
            _server_component_impl->send_command_ack(command_ack);
×
1798
            return CameraServer::Result::Success;
×
1799
        }
1800
        case CameraServer::CameraFeedback::Unknown:
×
1801
            // Fallthrough
1802
        default:
1803
            return CameraServer::Result::Error;
×
1804
    }
1805
}
1806

1807
std::optional<mavlink_command_ack_t>
1808
CameraServerImpl::process_track_point_command(const MavlinkCommandReceiver::CommandLong& command)
×
1809
{
1810
    if (!is_command_sender_ok(command)) {
×
1811
        LogWarn() << "Incoming track point command is for target sysid "
×
1812
                  << int(command.target_system_id) << " instead of "
×
1813
                  << int(_server_component_impl->get_own_system_id());
×
1814
        return std::nullopt;
×
1815
    }
1816

1817
    if (_tracking_point_callbacks.empty()) {
×
1818
        LogDebug() << "Track point requested with no user callback provided";
×
1819
        return _server_component_impl->make_command_ack_message(
×
1820
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1821
    }
1822

1823
    CameraServer::TrackPoint track_point{
×
1824
        command.params.param1, command.params.param2, command.params.param3};
×
1825

1826
    _last_track_point_command = command;
×
1827
    _tracking_point_callbacks(track_point);
×
1828
    // We don't send an ack but leave that to the user.
1829
    return std::nullopt;
×
1830
}
1831

1832
std::optional<mavlink_command_ack_t> CameraServerImpl::process_track_rectangle_command(
×
1833
    const MavlinkCommandReceiver::CommandLong& command)
1834
{
1835
    if (!is_command_sender_ok(command)) {
×
1836
        LogWarn() << "Incoming track rectangle command is for target sysid "
×
1837
                  << int(command.target_system_id) << " instead of "
×
1838
                  << int(_server_component_impl->get_own_system_id());
×
1839
        return std::nullopt;
×
1840
    }
1841

1842
    if (_tracking_rectangle_callbacks.empty()) {
×
1843
        LogDebug() << "Track rectangle requested with no user callback provided";
×
1844
        return _server_component_impl->make_command_ack_message(
×
1845
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1846
    }
1847

1848
    CameraServer::TrackRectangle track_rectangle{
×
1849
        command.params.param1, command.params.param2, command.params.param3, command.params.param4};
×
1850

1851
    _last_track_rectangle_command = command;
×
1852
    _tracking_rectangle_callbacks(track_rectangle);
×
1853
    // We don't send an ack but leave that to the user.
1854
    return std::nullopt;
×
1855
}
1856

1857
std::optional<mavlink_command_ack_t>
1858
CameraServerImpl::process_track_off_command(const MavlinkCommandReceiver::CommandLong& command)
×
1859
{
1860
    if (!is_command_sender_ok(command)) {
×
1861
        LogWarn() << "Incoming track off command is for target sysid "
×
1862
                  << int(command.target_system_id) << " instead of "
×
1863
                  << int(_server_component_impl->get_own_system_id());
×
1864
        return std::nullopt;
×
1865
    }
1866

1867
    if (_tracking_off_callbacks.empty()) {
×
1868
        LogDebug() << "Tracking off requested with no user callback provided";
×
1869
        return _server_component_impl->make_command_ack_message(
×
1870
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1871
    }
1872

1873
    _last_tracking_off_command = command;
×
1874
    _tracking_off_callbacks(0);
×
1875
    // We don't send an ack but leave that to the user.
1876
    return std::nullopt;
×
1877
}
1878

1879
std::optional<mavlink_command_ack_t>
1880
CameraServerImpl::process_set_message_interval(const MavlinkCommandReceiver::CommandLong& command)
×
1881
{
1882
    if (!is_command_sender_ok(command)) {
×
1883
        LogWarn() << "Incoming track off command is for target sysid "
×
1884
                  << int(command.target_system_id) << " instead of "
×
1885
                  << int(_server_component_impl->get_own_system_id());
×
1886
        return std::nullopt;
×
1887
    }
1888

1889
    auto message_id = static_cast<uint32_t>(command.params.param1);
×
1890
    auto interval_us = static_cast<int32_t>(command.params.param2);
×
1891
    UNUSED(message_id);
×
1892

1893
    // Interval value of -1 means to disable sending messages
1894
    if (interval_us < 0) {
×
1895
        stop_sending_tracking_status();
×
1896
    } else {
1897
        start_sending_tracking_status(interval_us);
×
1898
    }
1899

1900
    // Always send the "Accepted" result
1901
    return _server_component_impl->make_command_ack_message(
×
1902
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1903
}
1904

1905
void CameraServerImpl::send_tracking_status_with_interval(uint32_t interval_us)
×
1906
{
1907
    while (true) {
1908
        std::this_thread::sleep_for(std::chrono::microseconds{interval_us});
×
1909
        {
1910
            std::scoped_lock lg{_tracking_status_mutex};
×
1911
            if (!_sending_tracking_status) {
×
1912
                return;
×
1913
            }
1914
        }
×
1915
        _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
1916
            mavlink_message_t message;
1917
            std::lock_guard<std::mutex> lg{_tracking_status_mutex};
×
1918

1919
            // The message is filled based on current tracking mode
1920
            switch (_tracking_mode) {
×
1921
                default:
×
1922
                    // Fallthrough
1923
                case TrackingMode::NONE:
1924

1925
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
1926
                        mavlink_address.system_id,
×
1927
                        mavlink_address.component_id,
×
1928
                        channel,
1929
                        &message,
1930
                        CAMERA_TRACKING_STATUS_FLAGS_IDLE,
1931
                        CAMERA_TRACKING_MODE_NONE,
1932
                        CAMERA_TRACKING_TARGET_DATA_NONE,
1933
                        0.0f,
1934
                        0.0f,
1935
                        0.0f,
1936
                        0.0f,
1937
                        0.0f,
1938
                        0.0f,
1939
                        0.0f,
1940
                        0);
1941
                    break;
×
1942
                case TrackingMode::POINT:
×
1943

1944
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
1945
                        mavlink_address.system_id,
×
1946
                        mavlink_address.component_id,
×
1947
                        channel,
1948
                        &message,
1949
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
1950
                        CAMERA_TRACKING_MODE_POINT,
1951
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
1952
                        _tracked_point.point_x,
1953
                        _tracked_point.point_y,
1954
                        _tracked_point.radius,
1955
                        0.0f,
1956
                        0.0f,
1957
                        0.0f,
1958
                        0.0f,
1959
                        0);
1960
                    break;
×
1961

1962
                case TrackingMode::RECTANGLE:
×
1963

1964
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
1965
                        mavlink_address.system_id,
×
1966
                        mavlink_address.component_id,
×
1967
                        channel,
1968
                        &message,
1969
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
1970
                        CAMERA_TRACKING_MODE_RECTANGLE,
1971
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
1972
                        0.0f,
1973
                        0.0f,
1974
                        0.0f,
1975
                        _tracked_rectangle.top_left_corner_x,
1976
                        _tracked_rectangle.top_left_corner_y,
1977
                        _tracked_rectangle.bottom_right_corner_x,
1978
                        _tracked_rectangle.bottom_right_corner_y,
1979
                        0);
1980
                    break;
×
1981
            }
1982
            return message;
×
1983
        });
×
1984
    }
×
1985
}
1986

1987
void CameraServerImpl::start_sending_tracking_status(uint32_t interval_ms)
×
1988
{
1989
    // Stop sending status with the old interval
1990
    stop_sending_tracking_status();
×
1991
    _sending_tracking_status = true;
×
1992
    _tracking_status_sending_thread =
×
1993
        std::thread{&CameraServerImpl::send_tracking_status_with_interval, this, interval_ms};
×
1994
}
×
1995

1996
void CameraServerImpl::stop_sending_tracking_status()
×
1997
{
1998
    // Firstly, ask the other thread to stop sending the status
1999
    {
2000
        std::scoped_lock lg{_tracking_status_mutex};
×
2001
        _sending_tracking_status = false;
×
2002
    }
×
2003
    // If the thread was active, wait for it to finish
2004
    if (_tracking_status_sending_thread.joinable()) {
×
2005
        _tracking_status_sending_thread.join();
×
2006
    }
2007
}
×
2008

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