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

mavlink / MAVSDK / 11767930807

10 Nov 2024 07:33PM UTC coverage: 38.608% (+0.7%) from 37.921%
11767930807

push

github

web-flow
Merge pull request #2394 from mavlink/pr-consolidate-ci

Consolidate CI

12030 of 31159 relevant lines covered (38.61%)

243.33 hits per line

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

3.93
/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) :
1✔
11
    ServerPluginImplBase(server_component)
1✔
12
{
13
    _server_component_impl->register_plugin(this);
1✔
14
}
1✔
15

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

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

144
    _server_component_impl->register_mavlink_command_handler(
1✔
145
        MAV_CMD_CAMERA_TRACK_RECTANGLE,
146
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
147
            return process_track_rectangle_command(command);
×
148
        },
149
        this);
150

151
    _server_component_impl->register_mavlink_command_handler(
1✔
152
        MAV_CMD_CAMERA_STOP_TRACKING,
153
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
154
            return process_track_off_command(command);
×
155
        },
156
        this);
157
    _server_component_impl->register_mavlink_command_handler(
1✔
158
        MAV_CMD_SET_MESSAGE_INTERVAL,
159
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
160
            return process_set_message_interval(command);
×
161
        },
162
        this);
163
}
1✔
164

165
void CameraServerImpl::deinit()
1✔
166
{
167
    stop_image_capture_interval();
1✔
168
    _server_component_impl->unregister_all_mavlink_command_handlers(this);
1✔
169
}
1✔
170

171
bool CameraServerImpl::is_command_sender_ok(const MavlinkCommandReceiver::CommandLong& command)
×
172
{
173
    if (command.target_system_id != 0 &&
×
174
        command.target_system_id != _server_component_impl->get_own_system_id()) {
×
175
        return false;
×
176
    } else {
177
        return true;
×
178
    }
179
}
180

181
void CameraServerImpl::set_tracking_point_status(CameraServer::TrackPoint tracked_point)
×
182
{
183
    std::lock_guard<std::mutex> lg{_tracking_status_mutex};
×
184
    _tracking_mode = TrackingMode::POINT;
×
185
    _tracked_point = tracked_point;
×
186
}
×
187

188
void CameraServerImpl::set_tracking_rectangle_status(CameraServer::TrackRectangle tracked_rectangle)
×
189
{
190
    std::lock_guard<std::mutex> lg{_tracking_status_mutex};
×
191
    _tracking_mode = TrackingMode::RECTANGLE;
×
192
    _tracked_rectangle = tracked_rectangle;
×
193
}
×
194

195
void CameraServerImpl::set_tracking_off_status()
×
196
{
197
    std::lock_guard<std::mutex> lg{_tracking_status_mutex};
×
198
    _tracking_mode = TrackingMode::NONE;
×
199
}
×
200

201
bool CameraServerImpl::parse_version_string(const std::string& version_str)
×
202
{
203
    uint32_t unused;
×
204

205
    return parse_version_string(version_str, unused);
×
206
}
207

208
bool CameraServerImpl::parse_version_string(const std::string& version_str, uint32_t& version)
×
209
{
210
    // empty string means no version
211
    if (version_str.empty()) {
×
212
        version = 0;
×
213

214
        return true;
×
215
    }
216

217
    uint8_t major{}, minor{}, patch{}, dev{};
×
218

219
    auto ret = sscanf(version_str.c_str(), "%hhu.%hhu.%hhu.%hhu", &major, &minor, &patch, &dev);
×
220

221
    if (ret == EOF) {
×
222
        return false;
×
223
    }
224

225
    // pack version according to MAVLINK spec
226
    version = dev << 24 | patch << 16 | minor << 8 | major;
×
227

228
    return true;
×
229
}
230

231
CameraServer::Result CameraServerImpl::set_information(CameraServer::Information information)
×
232
{
233
    if (!parse_version_string(information.firmware_version)) {
×
234
        LogDebug() << "incorrectly formatted firmware version string: "
×
235
                   << information.firmware_version;
×
236
        return CameraServer::Result::WrongArgument;
×
237
    }
238

239
    // TODO: validate information.definition_file_uri
240

241
    _is_information_set = true;
×
242
    _information = information;
×
243

244
    return CameraServer::Result::Success;
×
245
}
246

247
CameraServer::Result
248
CameraServerImpl::set_video_streaming(CameraServer::VideoStreaming video_streaming)
×
249
{
250
    // TODO: validate uri length
251

252
    _is_video_streaming_set = true;
×
253
    _video_streaming = video_streaming;
×
254

255
    return CameraServer::Result::Success;
×
256
}
257

258
CameraServer::Result CameraServerImpl::set_in_progress(bool in_progress)
×
259
{
260
    _is_image_capture_in_progress = in_progress;
×
261

262
    send_capture_status();
×
263
    return CameraServer::Result::Success;
×
264
}
265

266
CameraServer::TakePhotoHandle
267
CameraServerImpl::subscribe_take_photo(const CameraServer::TakePhotoCallback& callback)
1✔
268
{
269
    return _take_photo_callbacks.subscribe(callback);
1✔
270
}
271

272
void CameraServerImpl::unsubscribe_take_photo(CameraServer::TakePhotoHandle handle)
×
273
{
274
    _take_photo_callbacks.unsubscribe(handle);
×
275
}
×
276

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

291
        _image_capture_count = capture_info.index;
×
292
    }
293

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

314
        case CameraServer::CameraFeedback::Failed: {
×
315
            auto command_ack = _server_component_impl->make_command_ack_message(
×
316
                _last_take_photo_command, MAV_RESULT_FAILED);
×
317
            _server_component_impl->send_command_ack(command_ack);
×
318
            return CameraServer::Result::Success;
×
319
        }
320
    }
321

322
    // REVISIT: Should we cache all CaptureInfo in memory for single image
323
    // captures so that we can respond to requests for lost CAMERA_IMAGE_CAPTURED
324
    // messages without calling back to user code?
325

326
    static const uint8_t camera_id = 0; // deprecated unused field
327

328
    const float attitude_quaternion[] = {
×
329
        capture_info.attitude_quaternion.w,
×
330
        capture_info.attitude_quaternion.x,
×
331
        capture_info.attitude_quaternion.y,
×
332
        capture_info.attitude_quaternion.z,
×
333
    };
×
334

335
    // There needs to be enough data to be copied mavlink internal.
336
    capture_info.file_url.resize(205);
×
337

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

361
    return CameraServer::Result::Success;
×
362
}
363

364
CameraServer::StartVideoHandle
365
CameraServerImpl::subscribe_start_video(const CameraServer::StartVideoCallback& callback)
×
366
{
367
    return _start_video_callbacks.subscribe(callback);
×
368
}
369

370
void CameraServerImpl::unsubscribe_start_video(CameraServer::StartVideoHandle handle)
×
371
{
372
    _start_video_callbacks.unsubscribe(handle);
×
373
}
×
374

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

404
CameraServer::StopVideoHandle
405
CameraServerImpl::subscribe_stop_video(const CameraServer::StopVideoCallback& callback)
×
406
{
407
    return _stop_video_callbacks.subscribe(callback);
×
408
}
409

410
void CameraServerImpl::unsubscribe_stop_video(CameraServer::StopVideoHandle handle)
×
411
{
412
    return _stop_video_callbacks.unsubscribe(handle);
×
413
}
414

415
CameraServer::Result
416
CameraServerImpl::respond_stop_video(CameraServer::CameraFeedback stop_video_feedback)
×
417
{
418
    switch (stop_video_feedback) {
×
419
        default:
×
420
            // Fallthrough
421
        case CameraServer::CameraFeedback::Unknown:
422
            return CameraServer::Result::Error;
×
423
        case CameraServer::CameraFeedback::Ok: {
×
424
            auto command_ack = _server_component_impl->make_command_ack_message(
×
425
                _last_stop_video_command, MAV_RESULT_ACCEPTED);
×
426
            _server_component_impl->send_command_ack(command_ack);
×
427
            return CameraServer::Result::Success;
×
428
        }
429
        case CameraServer::CameraFeedback::Busy: {
×
430
            auto command_ack = _server_component_impl->make_command_ack_message(
×
431
                _last_stop_video_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
432
            _server_component_impl->send_command_ack(command_ack);
×
433
            return CameraServer::Result::Success;
×
434
        }
435
        case CameraServer::CameraFeedback::Failed: {
×
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
    }
442
}
443

444
CameraServer::StartVideoStreamingHandle CameraServerImpl::subscribe_start_video_streaming(
×
445
    const CameraServer::StartVideoStreamingCallback& callback)
446
{
447
    return _start_video_streaming_callbacks.subscribe(callback);
×
448
}
449

450
void CameraServerImpl::unsubscribe_start_video_streaming(
×
451
    CameraServer::StartVideoStreamingHandle handle)
452
{
453
    return _start_video_streaming_callbacks.unsubscribe(handle);
×
454
}
455

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

485
CameraServer::StopVideoStreamingHandle CameraServerImpl::subscribe_stop_video_streaming(
×
486
    const CameraServer::StopVideoStreamingCallback& callback)
487
{
488
    return _stop_video_streaming_callbacks.subscribe(callback);
×
489
}
490

491
void CameraServerImpl::unsubscribe_stop_video_streaming(
×
492
    CameraServer::StopVideoStreamingHandle handle)
493
{
494
    return _stop_video_streaming_callbacks.unsubscribe(handle);
×
495
}
496

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

526
CameraServer::SetModeHandle
527
CameraServerImpl::subscribe_set_mode(const CameraServer::SetModeCallback& callback)
×
528
{
529
    return _set_mode_callbacks.subscribe(callback);
×
530
}
531

532
void CameraServerImpl::unsubscribe_set_mode(CameraServer::SetModeHandle handle)
×
533
{
534
    _set_mode_callbacks.unsubscribe(handle);
×
535
}
×
536

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

566
CameraServer::StorageInformationHandle CameraServerImpl::subscribe_storage_information(
×
567
    const CameraServer::StorageInformationCallback& callback)
568
{
569
    return _storage_information_callbacks.subscribe(callback);
×
570
}
571

572
void CameraServerImpl::unsubscribe_storage_information(
×
573
    CameraServer::StorageInformationHandle handle)
574
{
575
    _storage_information_callbacks.unsubscribe(handle);
×
576
}
×
577

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

608
    const uint8_t storage_count = 1;
×
609

610
    const float total_capacity = storage_information.total_storage_mib;
×
611
    const float used_capacity = storage_information.used_storage_mib;
×
612
    const float available_capacity = storage_information.available_storage_mib;
×
613
    const float read_speed = storage_information.read_speed_mib_s;
×
614
    const float write_speed = storage_information.write_speed_mib_s;
×
615

616
    auto status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
617
    switch (storage_information.storage_status) {
×
618
        case CameraServer::StorageInformation::StorageStatus::NotAvailable:
×
619
            status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
620
            break;
×
621
        case CameraServer::StorageInformation::StorageStatus::Unformatted:
×
622
            status = STORAGE_STATUS::STORAGE_STATUS_UNFORMATTED;
×
623
            break;
×
624
        case CameraServer::StorageInformation::StorageStatus::Formatted:
×
625
            status = STORAGE_STATUS::STORAGE_STATUS_READY;
×
626
            break;
×
627
        case CameraServer::StorageInformation::StorageStatus::NotSupported:
×
628
            status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED;
×
629
            break;
×
630
    }
631

632
    auto type = STORAGE_TYPE::STORAGE_TYPE_UNKNOWN;
×
633
    switch (storage_information.storage_type) {
×
634
        case CameraServer::StorageInformation::StorageType::UsbStick:
×
635
            type = STORAGE_TYPE::STORAGE_TYPE_USB_STICK;
×
636
            break;
×
637
        case CameraServer::StorageInformation::StorageType::Sd:
×
638
            type = STORAGE_TYPE::STORAGE_TYPE_SD;
×
639
            break;
×
640
        case CameraServer::StorageInformation::StorageType::Microsd:
×
641
            type = STORAGE_TYPE::STORAGE_TYPE_MICROSD;
×
642
            break;
×
643
        case CameraServer::StorageInformation::StorageType::Hd:
×
644
            type = STORAGE_TYPE::STORAGE_TYPE_HD;
×
645
            break;
×
646
        case CameraServer::StorageInformation::StorageType::Other:
×
647
            type = STORAGE_TYPE::STORAGE_TYPE_OTHER;
×
648
            break;
×
649
        default:
×
650
            break;
×
651
    }
652

653
    std::string name("");
×
654
    // This needs to be long enough, otherwise the memcpy in mavlink overflows.
655
    name.resize(32);
×
656
    const uint8_t storage_usage = 0;
×
657

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

680
    return CameraServer::Result::Success;
×
681
}
682

683
CameraServer::CaptureStatusHandle
684
CameraServerImpl::subscribe_capture_status(const CameraServer::CaptureStatusCallback& callback)
×
685
{
686
    return _capture_status_callbacks.subscribe(callback);
×
687
}
688

689
void CameraServerImpl::unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle)
×
690
{
691
    _capture_status_callbacks.unsubscribe(handle);
×
692
}
×
693

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

724
    _capture_status = capture_status;
×
725

726
    send_capture_status();
×
727

728
    return CameraServer::Result::Success;
×
729
}
730

731
CameraServer::FormatStorageHandle
732
CameraServerImpl::subscribe_format_storage(const CameraServer::FormatStorageCallback& callback)
×
733
{
734
    return _format_storage_callbacks.subscribe(callback);
×
735
}
736
void CameraServerImpl::unsubscribe_format_storage(CameraServer::FormatStorageHandle handle)
×
737
{
738
    _format_storage_callbacks.unsubscribe(handle);
×
739
}
×
740

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

770
CameraServer::ResetSettingsHandle
771
CameraServerImpl::subscribe_reset_settings(const CameraServer::ResetSettingsCallback& callback)
×
772
{
773
    return _reset_settings_callbacks.subscribe(callback);
×
774
}
775

776
void CameraServerImpl::unsubscribe_reset_settings(CameraServer::ResetSettingsHandle handle)
×
777
{
778
    _reset_settings_callbacks.unsubscribe(handle);
×
779
}
×
780

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

810
CameraServer::TrackingPointCommandHandle CameraServerImpl::subscribe_tracking_point_command(
×
811
    const CameraServer::TrackingPointCommandCallback& callback)
812
{
813
    return _tracking_point_callbacks.subscribe(callback);
×
814
}
815

816
void CameraServerImpl::unsubscribe_tracking_point_command(
×
817
    CameraServer::TrackingPointCommandHandle handle)
818
{
819
    _tracking_point_callbacks.unsubscribe(handle);
×
820
}
×
821

822
CameraServer::Result CameraServerImpl::respond_tracking_point_command(
×
823
    CameraServer::CameraFeedback tracking_point_feedback)
824
{
825
    switch (tracking_point_feedback) {
×
826
        default:
×
827
            // Fallthrough
828
        case CameraServer::CameraFeedback::Unknown:
829
            return CameraServer::Result::Error;
×
830
        case CameraServer::CameraFeedback::Ok: {
×
831
            auto command_ack = _server_component_impl->make_command_ack_message(
×
832
                _last_track_point_command, MAV_RESULT_ACCEPTED);
×
833
            _server_component_impl->send_command_ack(command_ack);
×
834
            break;
×
835
        }
836
        case CameraServer::CameraFeedback::Busy: {
×
837
            auto command_ack = _server_component_impl->make_command_ack_message(
×
838
                _last_track_point_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_track_point_command, MAV_RESULT_FAILED);
×
845
            _server_component_impl->send_command_ack(command_ack);
×
846
            return CameraServer::Result::Success;
×
847
        }
848
    }
849
    return CameraServer::Result::Success;
×
850
}
851

852
CameraServer::TrackingRectangleCommandHandle CameraServerImpl::subscribe_tracking_rectangle_command(
×
853
    const CameraServer::TrackingRectangleCommandCallback& callback)
854
{
855
    return _tracking_rectangle_callbacks.subscribe(callback);
×
856
}
857

858
void CameraServerImpl::unsubscribe_tracking_rectangle_command(
×
859
    CameraServer::TrackingRectangleCommandHandle handle)
860
{
861
    _tracking_rectangle_callbacks.unsubscribe(handle);
×
862
}
×
863

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

894
CameraServer::TrackingOffCommandHandle CameraServerImpl::subscribe_tracking_off_command(
×
895
    const CameraServer::TrackingOffCommandCallback& callback)
896
{
897
    return _tracking_off_callbacks.subscribe(callback);
×
898
}
899

900
void CameraServerImpl::unsubscribe_tracking_off_command(
×
901
    CameraServer::TrackingOffCommandHandle handle)
902
{
903
    _tracking_off_callbacks.unsubscribe(handle);
×
904
}
×
905

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

936
void CameraServerImpl::start_image_capture_interval(float interval_s, int32_t count, int32_t index)
×
937
{
938
    // If count == 0, it means capture "forever" until a stop command is received.
939
    auto remaining = std::make_shared<int32_t>(count == 0 ? INT32_MAX : count);
×
940

941
    _image_capture_timer_cookie = _server_component_impl->add_call_every(
×
942
        [this, remaining, index]() {
×
943
            LogDebug() << "capture image timer triggered";
×
944

945
            if (!_take_photo_callbacks.empty()) {
×
946
                _take_photo_callbacks(index);
×
947
                (*remaining)--;
×
948
            }
949

950
            if (*remaining == 0) {
×
951
                stop_image_capture_interval();
×
952
            }
953
        },
×
954
        interval_s);
955

956
    _is_image_capture_interval_set = true;
×
957
    _image_capture_timer_interval_s = interval_s;
×
958
}
×
959

960
void CameraServerImpl::stop_image_capture_interval()
1✔
961
{
962
    _server_component_impl->remove_call_every(_image_capture_timer_cookie);
1✔
963

964
    _is_image_capture_interval_set = false;
1✔
965
    _image_capture_timer_interval_s = 0;
1✔
966
}
1✔
967

968
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_information_request(
×
969
    const MavlinkCommandReceiver::CommandLong& command)
970
{
971
    LogWarn() << "Camera info request";
×
972
    auto capabilities = static_cast<bool>(command.params.param1);
×
973

974
    if (!capabilities) {
×
975
        LogDebug() << "early info return";
×
976
        return _server_component_impl->make_command_ack_message(
×
977
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
978
    }
979

980
    if (!_is_information_set) {
×
981
        return _server_component_impl->make_command_ack_message(
×
982
            command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED);
×
983
    }
984

985
    // ack needs to be sent before camera information message
986
    auto command_ack =
×
987
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
988
    _server_component_impl->send_command_ack(command_ack);
×
989
    LogDebug() << "sent info ack";
×
990

991
    // It is safe to ignore the return value of parse_version_string() here
992
    // since the string was already validated in set_information().
993
    uint32_t firmware_version;
×
994
    parse_version_string(_information.firmware_version, firmware_version);
×
995

996
    // capability flags are determined by subscriptions
997
    uint32_t capability_flags{};
×
998

999
    if (!_take_photo_callbacks.empty()) {
×
1000
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE;
×
1001
    }
1002

1003
    if (!_start_video_callbacks.empty()) {
×
1004
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
×
1005
    }
1006

1007
    if (!_set_mode_callbacks.empty()) {
×
1008
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES;
×
1009
    }
1010

1011
    if (_information.image_in_video_mode_supported) {
×
1012
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE;
×
1013
    }
1014

1015
    if (_information.video_in_image_mode_supported) {
×
1016
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE;
×
1017
    }
1018

1019
    if (_is_video_streaming_set) {
×
1020
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM;
×
1021
    }
1022

1023
    if (!_tracking_point_callbacks.empty()) {
×
1024
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT;
×
1025
    }
1026

1027
    if (!_tracking_rectangle_callbacks.empty()) {
×
1028
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE;
×
1029
    }
1030

1031
    if (!_zoom_range_callbacks.empty() || !_zoom_in_start_callbacks.empty() ||
×
1032
        !_zoom_out_start_callbacks.empty()) {
×
1033
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM;
×
1034
    }
1035

1036
    _information.vendor_name.resize(sizeof(mavlink_camera_information_t::vendor_name));
×
1037
    _information.model_name.resize(sizeof(mavlink_camera_information_t::model_name));
×
1038
    _information.definition_file_uri.resize(
×
1039
        sizeof(mavlink_camera_information_t::cam_definition_uri));
1040

1041
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
1042
        mavlink_message_t message{};
×
1043
        mavlink_msg_camera_information_pack_chan(
×
1044
            mavlink_address.system_id,
×
1045
            mavlink_address.component_id,
×
1046
            channel,
1047
            &message,
1048
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
1049
            reinterpret_cast<const uint8_t*>(_information.vendor_name.c_str()),
×
1050
            reinterpret_cast<const uint8_t*>(_information.model_name.c_str()),
×
1051
            firmware_version,
×
1052
            _information.focal_length_mm,
1053
            _information.horizontal_sensor_size_mm,
1054
            _information.vertical_sensor_size_mm,
1055
            _information.horizontal_resolution_px,
×
1056
            _information.vertical_resolution_px,
×
1057
            _information.lens_id,
×
1058
            capability_flags,
×
1059
            _information.definition_file_version,
×
1060
            _information.definition_file_uri.c_str(),
1061
            0);
1062
        return message;
×
1063
    });
1064
    LogDebug() << "sent info msg";
×
1065

1066
    // ack was already sent
1067
    return std::nullopt;
×
1068
}
1069

1070
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_settings_request(
×
1071
    const MavlinkCommandReceiver::CommandLong& command)
1072
{
1073
    auto settings = static_cast<bool>(command.params.param1);
×
1074

1075
    if (!settings) {
×
1076
        LogDebug() << "early settings return";
×
1077
        return _server_component_impl->make_command_ack_message(
×
1078
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1079
    }
1080

1081
    // ack needs to be sent before camera information message
1082
    auto command_ack =
×
1083
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1084
    _server_component_impl->send_command_ack(command_ack);
×
1085
    LogDebug() << "sent settings ack";
×
1086

1087
    // unsupported
1088
    const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE;
×
1089
    const float zoom_level = 0;
×
1090
    const float focus_level = 0;
×
1091

1092
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
1093
        mavlink_message_t message{};
×
1094
        mavlink_msg_camera_settings_pack_chan(
×
1095
            mavlink_address.system_id,
×
1096
            mavlink_address.component_id,
×
1097
            channel,
1098
            &message,
1099
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
1100
            mode_id,
1101
            zoom_level,
×
1102
            focus_level);
×
1103
        return message;
×
1104
    });
1105
    LogDebug() << "sent settings msg";
×
1106

1107
    // ack was already sent
1108
    return std::nullopt;
×
1109
}
1110

1111
std::optional<mavlink_command_ack_t> CameraServerImpl::process_storage_information_request(
×
1112
    const MavlinkCommandReceiver::CommandLong& command)
1113
{
1114
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
1115
    auto information = static_cast<bool>(command.params.param2);
×
1116

1117
    if (!information) {
×
1118
        return _server_component_impl->make_command_ack_message(
×
1119
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1120
    }
1121

1122
    if (_storage_information_callbacks.empty()) {
×
1123
        LogDebug()
×
1124
            << "Get storage information requested with no set storage information subscriber";
×
1125
        return _server_component_impl->make_command_ack_message(
×
1126
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1127
    }
1128

1129
    // TODO may need support multi storage id
1130
    _last_storage_id = storage_id;
×
1131

1132
    _last_storage_information_command = command;
×
1133
    _storage_information_callbacks(storage_id);
×
1134

1135
    // ack will be sent later in respond_storage_information
1136
    return std::nullopt;
×
1137
}
1138

1139
std::optional<mavlink_command_ack_t>
1140
CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLong& command)
×
1141
{
1142
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
1143
    auto format = static_cast<bool>(command.params.param2);
×
1144
    auto reset_image_log = static_cast<bool>(command.params.param3);
×
1145

1146
    UNUSED(format);
×
1147
    UNUSED(reset_image_log);
×
1148
    if (_format_storage_callbacks.empty()) {
×
1149
        LogDebug() << "process storage format requested with no storage format subscriber";
×
1150
        return _server_component_impl->make_command_ack_message(
×
1151
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1152
    }
1153

1154
    _last_format_storage_command = command;
×
1155
    _format_storage_callbacks(storage_id);
×
1156

1157
    return std::nullopt;
×
1158
}
1159

1160
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_capture_status_request(
×
1161
    const MavlinkCommandReceiver::CommandLong& command)
1162
{
1163
    auto capture_status = static_cast<bool>(command.params.param1);
×
1164

1165
    if (!capture_status) {
×
1166
        return _server_component_impl->make_command_ack_message(
×
1167
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1168
    }
1169

1170
    if (_capture_status_callbacks.empty()) {
×
1171
        LogDebug() << "process camera capture status requested with no capture status subscriber";
×
1172
        return _server_component_impl->make_command_ack_message(
×
1173
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1174
    }
1175

1176
    _last_capture_status_command = command;
×
1177

1178
    // may not need param for now ,just use zero
1179
    _capture_status_callbacks(0);
×
1180

1181
    // ack was already sent
1182
    return std::nullopt;
×
1183
}
1184

1185
void CameraServerImpl::send_capture_status()
×
1186
{
1187
    uint8_t image_status{};
×
1188
    if (_capture_status.image_status ==
×
1189
            CameraServer::CaptureStatus::ImageStatus::CaptureInProgress ||
×
1190
        _capture_status.image_status ==
×
1191
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress) {
1192
        image_status |= StatusFlags::IN_PROGRESS;
×
1193
    }
1194

1195
    if (_capture_status.image_status == CameraServer::CaptureStatus::ImageStatus::IntervalIdle ||
×
1196
        _capture_status.image_status ==
×
1197
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress ||
×
1198
        _is_image_capture_interval_set) {
×
1199
        image_status |= StatusFlags::INTERVAL_SET;
×
1200
    }
1201

1202
    uint8_t video_status = 0;
×
1203
    if (_capture_status.video_status == CameraServer::CaptureStatus::VideoStatus::Idle) {
×
1204
        video_status = 0;
×
1205
    } else if (
×
1206
        _capture_status.video_status ==
×
1207
        CameraServer::CaptureStatus::VideoStatus::CaptureInProgress) {
1208
        video_status = 1;
×
1209
    }
1210

1211
    const uint32_t recording_time_ms =
×
1212
        static_cast<uint32_t>(static_cast<double>(_capture_status.recording_time_s) * 1e3);
×
1213
    const float available_capacity = _capture_status.available_capacity_mib;
×
1214

1215
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
1216
        mavlink_message_t message{};
×
1217
        mavlink_msg_camera_capture_status_pack_chan(
×
1218
            mavlink_address.system_id,
×
1219
            mavlink_address.component_id,
×
1220
            channel,
1221
            &message,
1222
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
1223
            image_status,
×
1224
            video_status,
×
1225
            _image_capture_timer_interval_s,
1226
            recording_time_ms,
×
1227
            available_capacity,
×
1228
            _image_capture_count);
1229
        return message;
×
1230
    });
1231
}
×
1232

1233
std::optional<mavlink_command_ack_t>
1234
CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::CommandLong& command)
×
1235
{
1236
    auto reset = static_cast<bool>(command.params.param1);
×
1237

1238
    UNUSED(reset);
×
1239

1240
    if (_reset_settings_callbacks.empty()) {
×
1241
        LogDebug() << "reset camera settings requested with no camera settings subscriber";
×
1242
        return _server_component_impl->make_command_ack_message(
×
1243
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1244
    }
1245

1246
    _last_reset_settings_command = command;
×
1247
    _reset_settings_callbacks(0);
×
1248

1249
    return std::nullopt;
×
1250
}
1251

1252
std::optional<mavlink_command_ack_t>
1253
CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandLong& command)
×
1254
{
1255
    auto camera_mode = static_cast<CAMERA_MODE>(command.params.param2);
×
1256

1257
    if (_set_mode_callbacks.empty()) {
×
1258
        LogDebug() << "Set mode requested with no set mode subscriber";
×
1259
        return _server_component_impl->make_command_ack_message(
×
1260
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1261
    }
1262

1263
    // convert camera mode enum type
1264
    CameraServer::Mode convert_camera_mode = CameraServer::Mode::Unknown;
×
1265
    if (camera_mode == CAMERA_MODE_IMAGE) {
×
1266
        convert_camera_mode = CameraServer::Mode::Photo;
×
1267
    } else if (camera_mode == CAMERA_MODE_VIDEO) {
×
1268
        convert_camera_mode = CameraServer::Mode::Video;
×
1269
    }
1270

1271
    if (convert_camera_mode == CameraServer::Mode::Unknown) {
×
1272
        return _server_component_impl->make_command_ack_message(
×
1273
            command, MAV_RESULT::MAV_RESULT_DENIED);
×
1274
    }
1275

1276
    _last_set_mode_command = command;
×
1277
    _set_mode_callbacks(convert_camera_mode);
×
1278

1279
    return std::nullopt;
×
1280
}
1281

1282
std::optional<mavlink_command_ack_t>
1283
CameraServerImpl::process_set_camera_zoom(const MavlinkCommandReceiver::CommandLong& command)
×
1284
{
1285
    auto zoom_type = static_cast<CAMERA_ZOOM_TYPE>(command.params.param1);
×
1286
    auto zoom_value = command.params.param2;
×
1287

1288
    if (_zoom_in_start_callbacks.empty() && _zoom_out_start_callbacks.empty() &&
×
1289
        _zoom_stop_callbacks.empty() && _zoom_range_callbacks.empty()) {
×
1290
        LogWarn() << "No camera zoom is supported";
×
1291
        return _server_component_impl->make_command_ack_message(
×
1292
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1293
    }
1294

1295
    auto unsupported = [&]() {
×
1296
        LogWarn() << "unsupported set camera zoom type (" << (int)zoom_type << ") request";
×
1297
    };
×
1298

1299
    switch (zoom_type) {
×
1300
        case ZOOM_TYPE_CONTINUOUS:
×
1301
            if (zoom_value == -1.f) {
×
1302
                if (_zoom_out_start_callbacks.empty()) {
×
1303
                    unsupported();
×
1304
                    return _server_component_impl->make_command_ack_message(
×
1305
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1306
                } else {
1307
                    _last_zoom_out_start_command = command;
×
1308
                    int dummy = 0;
×
1309
                    _zoom_out_start_callbacks(dummy);
×
1310
                }
1311
            } else if (zoom_value == 1.f) {
×
1312
                if (_zoom_in_start_callbacks.empty()) {
×
1313
                    unsupported();
×
1314
                    return _server_component_impl->make_command_ack_message(
×
1315
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1316
                } else {
1317
                    _last_zoom_in_start_command = command;
×
1318
                    int dummy = 0;
×
1319
                    _zoom_in_start_callbacks(dummy);
×
1320
                }
1321
            } else if (zoom_value == 0.f) {
×
1322
                if (_zoom_stop_callbacks.empty()) {
×
1323
                    unsupported();
×
1324
                    return _server_component_impl->make_command_ack_message(
×
1325
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1326
                } else {
1327
                    _last_zoom_stop_command = command;
×
1328
                    int dummy = 0;
×
1329
                    _zoom_stop_callbacks(dummy);
×
1330
                }
1331
            } else {
1332
                LogWarn() << "Invalid zoom value";
×
1333
                return _server_component_impl->make_command_ack_message(
×
1334
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1335
            }
1336
            break;
×
1337
        case ZOOM_TYPE_RANGE:
×
1338
            if (_zoom_range_callbacks.empty()) {
×
1339
                unsupported();
×
1340
                return _server_component_impl->make_command_ack_message(
×
1341
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1342

1343
            } else {
1344
                _last_zoom_range_command = command;
×
1345
                _zoom_range_callbacks(zoom_value);
×
1346
            }
1347
            break;
×
1348
        case ZOOM_TYPE_STEP:
×
1349
        // Fallthrough
1350
        case ZOOM_TYPE_FOCAL_LENGTH:
1351
        // Fallthrough
1352
        case ZOOM_TYPE_HORIZONTAL_FOV:
1353
        // Fallthrough
1354
        default:
1355
            unsupported();
×
1356
            return _server_component_impl->make_command_ack_message(
×
1357
                command, MAV_RESULT::MAV_RESULT_DENIED);
×
1358
            break;
1359
    }
1360

1361
    // For any success so far, we don't ack yet, but later when the respond function is called.
1362
    return std::nullopt;
×
1363
}
1364

1365
std::optional<mavlink_command_ack_t>
1366
CameraServerImpl::process_set_camera_focus(const MavlinkCommandReceiver::CommandLong& command)
×
1367
{
1368
    auto focus_type = static_cast<SET_FOCUS_TYPE>(command.params.param1);
×
1369
    auto focus_value = command.params.param2;
×
1370

1371
    UNUSED(focus_type);
×
1372
    UNUSED(focus_value);
×
1373

1374
    LogDebug() << "unsupported set camera focus request";
×
1375

1376
    return _server_component_impl->make_command_ack_message(
×
1377
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1378
}
1379

1380
std::optional<mavlink_command_ack_t>
1381
CameraServerImpl::process_set_storage_usage(const MavlinkCommandReceiver::CommandLong& command)
×
1382
{
1383
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
1384
    auto usage = static_cast<STORAGE_USAGE_FLAG>(command.params.param2);
×
1385

1386
    UNUSED(storage_id);
×
1387
    UNUSED(usage);
×
1388

1389
    LogDebug() << "unsupported set storage usage request";
×
1390

1391
    return _server_component_impl->make_command_ack_message(
×
1392
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1393
}
1394

1395
std::optional<mavlink_command_ack_t>
1396
CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1397
{
1398
    auto interval_s = command.params.param2;
×
1399
    auto total_images = static_cast<int32_t>(command.params.param3);
×
1400
    auto seq_number = static_cast<int32_t>(command.params.param4);
×
1401

1402
    LogDebug() << "received image start capture request - interval: " << +interval_s
×
1403
               << " total: " << +total_images << " index: " << +seq_number;
×
1404

1405
    // TODO: validate parameters and return MAV_RESULT_DENIED not valid
1406

1407
    stop_image_capture_interval();
×
1408

1409
    if (_take_photo_callbacks.empty()) {
×
1410
        LogDebug() << "image capture requested with no take photo subscriber";
×
1411
        return _server_component_impl->make_command_ack_message(
×
1412
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1413
    }
1414

1415
    // single image capture
1416
    if (total_images == 1) {
×
1417
        // MAV_RESULT_ACCEPTED must be sent before CAMERA_IMAGE_CAPTURED
1418
        auto command_ack = _server_component_impl->make_command_ack_message(
×
1419
            command, MAV_RESULT::MAV_RESULT_IN_PROGRESS);
1420
        _server_component_impl->send_command_ack(command_ack);
×
1421

1422
        _last_take_photo_command = command;
×
1423

1424
        _take_photo_callbacks(seq_number);
×
1425

1426
        return std::nullopt;
×
1427
    }
1428

1429
    start_image_capture_interval(interval_s, total_images, seq_number);
×
1430

1431
    return _server_component_impl->make_command_ack_message(
×
1432
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1433
}
1434

1435
std::optional<mavlink_command_ack_t>
1436
CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1437
{
1438
    LogDebug() << "received image stop capture request";
×
1439

1440
    // REVISIT: should we return something other that MAV_RESULT_ACCEPTED if
1441
    // there is not currently a capture interval active?
1442
    stop_image_capture_interval();
×
1443

1444
    return _server_component_impl->make_command_ack_message(
×
1445
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1446
}
1447

1448
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_image_capture_request(
×
1449
    const MavlinkCommandReceiver::CommandLong& command)
1450
{
1451
    auto seq_number = static_cast<uint32_t>(command.params.param1);
×
1452

1453
    UNUSED(seq_number);
×
1454

1455
    LogDebug() << "unsupported image capture request";
×
1456

1457
    return _server_component_impl->make_command_ack_message(
×
1458
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1459
}
1460

1461
std::optional<mavlink_command_ack_t>
1462
CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1463
{
1464
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1465
    auto status_frequency = command.params.param2;
×
1466

1467
    UNUSED(status_frequency);
×
1468

1469
    if (_start_video_callbacks.empty()) {
×
1470
        LogDebug() << "video start capture requested with no video start capture subscriber";
×
1471
        return _server_component_impl->make_command_ack_message(
×
1472
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1473
    }
1474

1475
    _last_start_video_command = command;
×
1476
    _start_video_callbacks(stream_id);
×
1477

1478
    return std::nullopt;
×
1479
}
1480

1481
std::optional<mavlink_command_ack_t>
1482
CameraServerImpl::process_video_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1483
{
1484
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1485

1486
    if (_stop_video_callbacks.empty()) {
×
1487
        LogDebug() << "video stop capture requested with no video stop capture subscriber";
×
1488
        return _server_component_impl->make_command_ack_message(
×
1489
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1490
    }
1491

1492
    _last_stop_video_command = command;
×
1493
    _stop_video_callbacks(stream_id);
×
1494

1495
    return std::nullopt;
×
1496
}
1497

1498
std::optional<mavlink_command_ack_t>
1499
CameraServerImpl::process_video_start_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1500
{
1501
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1502

1503
    if (_start_video_streaming_callbacks.empty()) {
×
1504
        LogDebug() << "video start streaming requested with no video start streaming subscriber";
×
1505
        return _server_component_impl->make_command_ack_message(
×
1506
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1507
    }
1508

1509
    _last_start_video_streaming_command = command;
×
1510
    _start_video_streaming_callbacks(stream_id);
×
1511

1512
    return std::nullopt;
×
1513
}
1514

1515
std::optional<mavlink_command_ack_t>
1516
CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1517
{
1518
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1519

1520
    if (_stop_video_streaming_callbacks.empty()) {
×
1521
        LogDebug() << "video stop streaming requested with no video stop streaming subscriber";
×
1522
        return _server_component_impl->make_command_ack_message(
×
1523
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1524
    }
1525

1526
    _last_stop_video_streaming_command = command;
×
1527
    _stop_video_streaming_callbacks(stream_id);
×
1528

1529
    return std::nullopt;
×
1530
}
1531

1532
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_information_request(
×
1533
    const MavlinkCommandReceiver::CommandLong& command)
1534
{
1535
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1536

1537
    UNUSED(stream_id);
×
1538

1539
    if (_is_video_streaming_set) {
×
1540
        auto command_ack = _server_component_impl->make_command_ack_message(
×
1541
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
1542
        _server_component_impl->send_command_ack(command_ack);
×
1543
        LogDebug() << "sent video streaming ack";
×
1544

1545
        const char name[32] = "";
×
1546

1547
        _video_streaming.rtsp_uri.resize(sizeof(mavlink_video_stream_information_t::uri));
×
1548

1549
        mavlink_message_t msg{};
×
1550
        mavlink_msg_video_stream_information_pack(
×
1551
            _server_component_impl->get_own_system_id(),
×
1552
            _server_component_impl->get_own_component_id(),
×
1553
            &msg,
1554
            0, // Stream id
1555
            0, // Count
1556
            VIDEO_STREAM_TYPE_RTSP,
1557
            VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1558
            0, // famerate
1559
            0, // resolution horizontal
1560
            0, // resolution vertical
1561
            0, // bitrate
1562
            0, // rotation
1563
            0, // horizontal field of view
1564
            name,
1565
            _video_streaming.rtsp_uri.c_str());
1566

1567
        _server_component_impl->send_message(msg);
×
1568

1569
        // Ack already sent.
1570
        return std::nullopt;
×
1571

1572
    } else {
1573
        return _server_component_impl->make_command_ack_message(
×
1574
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1575
    }
1576
}
1577

1578
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_status_request(
×
1579
    const MavlinkCommandReceiver::CommandLong& command)
1580
{
1581
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1582

1583
    UNUSED(stream_id);
×
1584

1585
    if (!_is_video_streaming_set) {
×
1586
        return _server_component_impl->make_command_ack_message(
×
1587
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1588
    }
1589

1590
    auto command_ack =
×
1591
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1592
    _server_component_impl->send_command_ack(command_ack);
×
1593
    LogDebug() << "sent video streaming ack";
×
1594

1595
    mavlink_message_t msg{};
×
1596
    mavlink_msg_video_stream_status_pack(
×
1597
        _server_component_impl->get_own_system_id(),
×
1598
        _server_component_impl->get_own_component_id(),
×
1599
        &msg,
1600
        0, // Stream id
1601
        VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1602
        0, // framerate
1603
        0, // resolution horizontal
1604
        0, // resolution vertical
1605
        0, // bitrate
1606
        0, // rotation
1607
        0 // horizontal field of view
1608
    );
1609
    _server_component_impl->send_message(msg);
×
1610

1611
    // ack was already sent
1612
    return std::nullopt;
×
1613
}
1614

1615
CameraServer::ZoomInStartHandle
1616
CameraServerImpl::subscribe_zoom_in_start(const CameraServer::ZoomInStartCallback& callback)
×
1617
{
1618
    return _zoom_in_start_callbacks.subscribe(callback);
×
1619
}
1620

1621
void CameraServerImpl::unsubscribe_zoom_in_start(CameraServer::ZoomInStartHandle handle)
×
1622
{
1623
    _zoom_in_start_callbacks.unsubscribe(handle);
×
1624
}
×
1625

1626
CameraServer::Result
1627
CameraServerImpl::respond_zoom_in_start(CameraServer::CameraFeedback zoom_in_start_feedback)
×
1628
{
1629
    switch (zoom_in_start_feedback) {
×
1630
        default:
×
1631
            // Fallthrough
1632
        case CameraServer::CameraFeedback::Unknown:
1633
            return CameraServer::Result::Error;
×
1634
        case CameraServer::CameraFeedback::Ok: {
×
1635
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1636
                _last_zoom_in_start_command, MAV_RESULT_ACCEPTED);
×
1637
            _server_component_impl->send_command_ack(command_ack);
×
1638
            return CameraServer::Result::Success;
×
1639
        }
1640
        case CameraServer::CameraFeedback::Busy: {
×
1641
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1642
                _last_zoom_in_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1643
            _server_component_impl->send_command_ack(command_ack);
×
1644
            return CameraServer::Result::Success;
×
1645
        }
1646
        case CameraServer::CameraFeedback::Failed: {
×
1647
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1648
                _last_zoom_in_start_command, MAV_RESULT_FAILED);
×
1649
            _server_component_impl->send_command_ack(command_ack);
×
1650
            return CameraServer::Result::Success;
×
1651
        }
1652
    }
1653
}
1654

1655
CameraServer::ZoomOutStartHandle
1656
CameraServerImpl::subscribe_zoom_out_start(const CameraServer::ZoomOutStartCallback& callback)
×
1657
{
1658
    return _zoom_out_start_callbacks.subscribe(callback);
×
1659
}
1660

1661
void CameraServerImpl::unsubscribe_zoom_out_start(CameraServer::ZoomOutStartHandle handle)
×
1662
{
1663
    _zoom_out_start_callbacks.unsubscribe(handle);
×
1664
}
×
1665

1666
CameraServer::Result
1667
CameraServerImpl::respond_zoom_out_start(CameraServer::CameraFeedback zoom_out_start_feedback)
×
1668
{
1669
    switch (zoom_out_start_feedback) {
×
1670
        default:
×
1671
            // Fallthrough
1672
        case CameraServer::CameraFeedback::Unknown:
1673
            return CameraServer::Result::Error;
×
1674
        case CameraServer::CameraFeedback::Ok: {
×
1675
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1676
                _last_zoom_out_start_command, MAV_RESULT_ACCEPTED);
×
1677
            _server_component_impl->send_command_ack(command_ack);
×
1678
            return CameraServer::Result::Success;
×
1679
        }
1680
        case CameraServer::CameraFeedback::Busy: {
×
1681
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1682
                _last_zoom_out_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1683
            _server_component_impl->send_command_ack(command_ack);
×
1684
            return CameraServer::Result::Success;
×
1685
        }
1686
        case CameraServer::CameraFeedback::Failed: {
×
1687
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1688
                _last_zoom_out_start_command, MAV_RESULT_FAILED);
×
1689
            _server_component_impl->send_command_ack(command_ack);
×
1690
            return CameraServer::Result::Success;
×
1691
        }
1692
    }
1693
}
1694

1695
CameraServer::ZoomStopHandle
1696
CameraServerImpl::subscribe_zoom_stop(const CameraServer::ZoomStopCallback& callback)
×
1697
{
1698
    return _zoom_stop_callbacks.subscribe(callback);
×
1699
}
1700

1701
void CameraServerImpl::unsubscribe_zoom_stop(CameraServer::ZoomStopHandle handle)
×
1702
{
1703
    _zoom_stop_callbacks.unsubscribe(handle);
×
1704
}
×
1705

1706
CameraServer::Result
1707
CameraServerImpl::respond_zoom_stop(CameraServer::CameraFeedback zoom_stop_feedback)
×
1708
{
1709
    switch (zoom_stop_feedback) {
×
1710
        default:
×
1711
            // Fallthrough
1712
        case CameraServer::CameraFeedback::Unknown:
1713
            return CameraServer::Result::Error;
×
1714
        case CameraServer::CameraFeedback::Ok: {
×
1715
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1716
                _last_zoom_stop_command, MAV_RESULT_ACCEPTED);
×
1717
            _server_component_impl->send_command_ack(command_ack);
×
1718
            return CameraServer::Result::Success;
×
1719
        }
1720
        case CameraServer::CameraFeedback::Busy: {
×
1721
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1722
                _last_zoom_stop_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1723
            _server_component_impl->send_command_ack(command_ack);
×
1724
            return CameraServer::Result::Success;
×
1725
        }
1726
        case CameraServer::CameraFeedback::Failed: {
×
1727
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1728
                _last_zoom_stop_command, MAV_RESULT_FAILED);
×
1729
            _server_component_impl->send_command_ack(command_ack);
×
1730
            return CameraServer::Result::Success;
×
1731
        }
1732
    }
1733
}
1734

1735
CameraServer::ZoomRangeHandle
1736
CameraServerImpl::subscribe_zoom_range(const CameraServer::ZoomRangeCallback& callback)
×
1737
{
1738
    return _zoom_range_callbacks.subscribe(callback);
×
1739
}
1740

1741
void CameraServerImpl::unsubscribe_zoom_range(CameraServer::ZoomRangeHandle handle)
×
1742
{
1743
    _zoom_range_callbacks.unsubscribe(handle);
×
1744
}
×
1745

1746
CameraServer::Result
1747
CameraServerImpl::respond_zoom_range(CameraServer::CameraFeedback zoom_range_feedback)
×
1748
{
1749
    switch (zoom_range_feedback) {
×
1750
        case CameraServer::CameraFeedback::Ok: {
×
1751
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1752
                _last_zoom_range_command, MAV_RESULT_ACCEPTED);
×
1753
            _server_component_impl->send_command_ack(command_ack);
×
1754
            return CameraServer::Result::Success;
×
1755
        }
1756
        case CameraServer::CameraFeedback::Busy: {
×
1757
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1758
                _last_zoom_range_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1759
            _server_component_impl->send_command_ack(command_ack);
×
1760
            return CameraServer::Result::Success;
×
1761
        }
1762
        case CameraServer::CameraFeedback::Failed: {
×
1763
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1764
                _last_zoom_range_command, MAV_RESULT_FAILED);
×
1765
            _server_component_impl->send_command_ack(command_ack);
×
1766
            return CameraServer::Result::Success;
×
1767
        }
1768
        case CameraServer::CameraFeedback::Unknown:
×
1769
            // Fallthrough
1770
        default:
1771
            return CameraServer::Result::Error;
×
1772
    }
1773
}
1774

1775
std::optional<mavlink_command_ack_t>
1776
CameraServerImpl::process_track_point_command(const MavlinkCommandReceiver::CommandLong& command)
×
1777
{
1778
    if (!is_command_sender_ok(command)) {
×
1779
        LogWarn() << "Incoming track point command is for target sysid "
×
1780
                  << int(command.target_system_id) << " instead of "
×
1781
                  << int(_server_component_impl->get_own_system_id());
×
1782
        return std::nullopt;
×
1783
    }
1784

1785
    if (_tracking_point_callbacks.empty()) {
×
1786
        LogDebug() << "Track point requested with no user callback provided";
×
1787
        return _server_component_impl->make_command_ack_message(
×
1788
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1789
    }
1790

1791
    CameraServer::TrackPoint track_point{
×
1792
        command.params.param1, command.params.param2, command.params.param3};
×
1793

1794
    _last_track_point_command = command;
×
1795
    _tracking_point_callbacks(track_point);
×
1796
    // We don't send an ack but leave that to the user.
1797
    return std::nullopt;
×
1798
}
1799

1800
std::optional<mavlink_command_ack_t> CameraServerImpl::process_track_rectangle_command(
×
1801
    const MavlinkCommandReceiver::CommandLong& command)
1802
{
1803
    if (!is_command_sender_ok(command)) {
×
1804
        LogWarn() << "Incoming track rectangle command is for target sysid "
×
1805
                  << int(command.target_system_id) << " instead of "
×
1806
                  << int(_server_component_impl->get_own_system_id());
×
1807
        return std::nullopt;
×
1808
    }
1809

1810
    if (_tracking_rectangle_callbacks.empty()) {
×
1811
        LogDebug() << "Track rectangle requested with no user callback provided";
×
1812
        return _server_component_impl->make_command_ack_message(
×
1813
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1814
    }
1815

1816
    CameraServer::TrackRectangle track_rectangle{
×
1817
        command.params.param1, command.params.param2, command.params.param3, command.params.param4};
×
1818

1819
    _last_track_rectangle_command = command;
×
1820
    _tracking_rectangle_callbacks(track_rectangle);
×
1821
    // We don't send an ack but leave that to the user.
1822
    return std::nullopt;
×
1823
}
1824

1825
std::optional<mavlink_command_ack_t>
1826
CameraServerImpl::process_track_off_command(const MavlinkCommandReceiver::CommandLong& command)
×
1827
{
1828
    if (!is_command_sender_ok(command)) {
×
1829
        LogWarn() << "Incoming track off command is for target sysid "
×
1830
                  << int(command.target_system_id) << " instead of "
×
1831
                  << int(_server_component_impl->get_own_system_id());
×
1832
        return std::nullopt;
×
1833
    }
1834

1835
    if (_tracking_off_callbacks.empty()) {
×
1836
        LogDebug() << "Tracking off requested with no user callback provided";
×
1837
        return _server_component_impl->make_command_ack_message(
×
1838
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1839
    }
1840

1841
    _last_tracking_off_command = command;
×
1842
    _tracking_off_callbacks(0);
×
1843
    // We don't send an ack but leave that to the user.
1844
    return std::nullopt;
×
1845
}
1846

1847
std::optional<mavlink_command_ack_t>
1848
CameraServerImpl::process_set_message_interval(const MavlinkCommandReceiver::CommandLong& command)
×
1849
{
1850
    if (!is_command_sender_ok(command)) {
×
1851
        LogWarn() << "Incoming track off command is for target sysid "
×
1852
                  << int(command.target_system_id) << " instead of "
×
1853
                  << int(_server_component_impl->get_own_system_id());
×
1854
        return std::nullopt;
×
1855
    }
1856

1857
    auto message_id = static_cast<uint32_t>(command.params.param1);
×
1858
    auto interval_us = static_cast<int32_t>(command.params.param2);
×
1859
    UNUSED(message_id);
×
1860

1861
    // Interval value of -1 means to disable sending messages
1862
    if (interval_us < 0) {
×
1863
        stop_sending_tracking_status();
×
1864
    } else {
1865
        start_sending_tracking_status(interval_us);
×
1866
    }
1867

1868
    // Always send the "Accepted" result
1869
    return _server_component_impl->make_command_ack_message(
×
1870
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1871
}
1872

1873
void CameraServerImpl::send_tracking_status_with_interval(uint32_t interval_us)
×
1874
{
1875
    while (true) {
1876
        std::this_thread::sleep_for(std::chrono::microseconds{interval_us});
×
1877
        {
1878
            std::scoped_lock lg{_tracking_status_mutex};
×
1879
            if (!_sending_tracking_status) {
×
1880
                return;
×
1881
            }
1882
        }
×
1883
        _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
1884
            mavlink_message_t message;
1885
            std::lock_guard<std::mutex> lg{_tracking_status_mutex};
×
1886

1887
            // The message is filled based on current tracking mode
1888
            switch (_tracking_mode) {
×
1889
                default:
×
1890
                    // Fallthrough
1891
                case TrackingMode::NONE:
1892

1893
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
1894
                        mavlink_address.system_id,
×
1895
                        mavlink_address.component_id,
×
1896
                        channel,
1897
                        &message,
1898
                        CAMERA_TRACKING_STATUS_FLAGS_IDLE,
1899
                        CAMERA_TRACKING_MODE_NONE,
1900
                        CAMERA_TRACKING_TARGET_DATA_NONE,
1901
                        0.0f,
1902
                        0.0f,
1903
                        0.0f,
1904
                        0.0f,
1905
                        0.0f,
1906
                        0.0f,
1907
                        0.0f);
1908
                    break;
×
1909
                case TrackingMode::POINT:
×
1910

1911
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
1912
                        mavlink_address.system_id,
×
1913
                        mavlink_address.component_id,
×
1914
                        channel,
1915
                        &message,
1916
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
1917
                        CAMERA_TRACKING_MODE_POINT,
1918
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
1919
                        _tracked_point.point_x,
1920
                        _tracked_point.point_y,
1921
                        _tracked_point.radius,
1922
                        0.0f,
1923
                        0.0f,
1924
                        0.0f,
1925
                        0.0f);
1926
                    break;
×
1927

1928
                case TrackingMode::RECTANGLE:
×
1929

1930
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
1931
                        mavlink_address.system_id,
×
1932
                        mavlink_address.component_id,
×
1933
                        channel,
1934
                        &message,
1935
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
1936
                        CAMERA_TRACKING_MODE_RECTANGLE,
1937
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
1938
                        0.0f,
1939
                        0.0f,
1940
                        0.0f,
1941
                        _tracked_rectangle.top_left_corner_x,
1942
                        _tracked_rectangle.top_left_corner_y,
1943
                        _tracked_rectangle.bottom_right_corner_x,
1944
                        _tracked_rectangle.bottom_right_corner_y);
1945
                    break;
×
1946
            }
1947
            return message;
×
1948
        });
×
1949
    }
×
1950
}
1951

1952
void CameraServerImpl::start_sending_tracking_status(uint32_t interval_ms)
×
1953
{
1954
    // Stop sending status with the old interval
1955
    stop_sending_tracking_status();
×
1956
    _sending_tracking_status = true;
×
1957
    _tracking_status_sending_thread =
×
1958
        std::thread{&CameraServerImpl::send_tracking_status_with_interval, this, interval_ms};
×
1959
}
×
1960

1961
void CameraServerImpl::stop_sending_tracking_status()
×
1962
{
1963
    // Firstly, ask the other thread to stop sending the status
1964
    {
1965
        std::scoped_lock lg{_tracking_status_mutex};
×
1966
        _sending_tracking_status = false;
×
1967
    }
×
1968
    // If the thread was active, wait for it to finish
1969
    if (_tracking_status_sending_thread.joinable()) {
×
1970
        _tracking_status_sending_thread.join();
×
1971
    }
1972
}
×
1973

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