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

mavlink / MAVSDK / 11452150858

22 Oct 2024 02:32AM CUT coverage: 37.403% (+0.02%) from 37.381%
11452150858

push

github

web-flow
camera_server: prevent double ack+message (#2430)

It turns out we were sending the ack and message for storage information
as well as capture status twice, once directly in the request handler
callback, and once the MAVSDK user would call the respond function.

We should only call it in the respond function, not in the callback.

11105 of 29690 relevant lines covered (37.4%)

255.6 hits per line

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

3.96
/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()
1✔
17
{
18
    _server_component_impl->unregister_plugin(this);
1✔
19
}
1✔
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 (_is_video_streaming_set) {
×
1012
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM;
×
1013
    }
1014

1015
    if (!_tracking_point_callbacks.empty()) {
×
1016
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT;
×
1017
    }
1018

1019
    if (!_tracking_rectangle_callbacks.empty()) {
×
1020
        capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE;
×
1021
    }
1022

1023
    _information.vendor_name.resize(sizeof(mavlink_camera_information_t::vendor_name));
×
1024
    _information.model_name.resize(sizeof(mavlink_camera_information_t::model_name));
×
1025
    _information.definition_file_uri.resize(
×
1026
        sizeof(mavlink_camera_information_t::cam_definition_uri));
1027

1028
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
1029
        mavlink_message_t message{};
×
1030
        mavlink_msg_camera_information_pack_chan(
×
1031
            mavlink_address.system_id,
×
1032
            mavlink_address.component_id,
×
1033
            channel,
1034
            &message,
1035
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
1036
            reinterpret_cast<const uint8_t*>(_information.vendor_name.c_str()),
×
1037
            reinterpret_cast<const uint8_t*>(_information.model_name.c_str()),
×
1038
            firmware_version,
×
1039
            _information.focal_length_mm,
1040
            _information.horizontal_sensor_size_mm,
1041
            _information.vertical_sensor_size_mm,
1042
            _information.horizontal_resolution_px,
×
1043
            _information.vertical_resolution_px,
×
1044
            _information.lens_id,
×
1045
            capability_flags,
×
1046
            _information.definition_file_version,
×
1047
            _information.definition_file_uri.c_str(),
1048
            0);
1049
        return message;
×
1050
    });
1051
    LogDebug() << "sent info msg";
×
1052

1053
    // ack was already sent
1054
    return std::nullopt;
×
1055
}
1056

1057
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_settings_request(
×
1058
    const MavlinkCommandReceiver::CommandLong& command)
1059
{
1060
    auto settings = static_cast<bool>(command.params.param1);
×
1061

1062
    if (!settings) {
×
1063
        LogDebug() << "early settings return";
×
1064
        return _server_component_impl->make_command_ack_message(
×
1065
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1066
    }
1067

1068
    // ack needs to be sent before camera information message
1069
    auto command_ack =
×
1070
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1071
    _server_component_impl->send_command_ack(command_ack);
×
1072
    LogDebug() << "sent settings ack";
×
1073

1074
    // unsupported
1075
    const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE;
×
1076
    const float zoom_level = 0;
×
1077
    const float focus_level = 0;
×
1078

1079
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
1080
        mavlink_message_t message{};
×
1081
        mavlink_msg_camera_settings_pack_chan(
×
1082
            mavlink_address.system_id,
×
1083
            mavlink_address.component_id,
×
1084
            channel,
1085
            &message,
1086
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
1087
            mode_id,
1088
            zoom_level,
×
1089
            focus_level);
×
1090
        return message;
×
1091
    });
1092
    LogDebug() << "sent settings msg";
×
1093

1094
    // ack was already sent
1095
    return std::nullopt;
×
1096
}
1097

1098
std::optional<mavlink_command_ack_t> CameraServerImpl::process_storage_information_request(
×
1099
    const MavlinkCommandReceiver::CommandLong& command)
1100
{
1101
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
1102
    auto information = static_cast<bool>(command.params.param2);
×
1103

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

1109
    if (_storage_information_callbacks.empty()) {
×
1110
        LogDebug()
×
1111
            << "Get storage information requested with no set storage information subscriber";
×
1112
        return _server_component_impl->make_command_ack_message(
×
1113
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1114
    }
1115

1116
    // TODO may need support multi storage id
1117
    _last_storage_id = storage_id;
×
1118

1119
    _last_storage_information_command = command;
×
1120
    _storage_information_callbacks(storage_id);
×
1121

1122
    // ack will be sent later in respond_storage_information
1123
    return std::nullopt;
×
1124
}
1125

1126
std::optional<mavlink_command_ack_t>
1127
CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLong& command)
×
1128
{
1129
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
1130
    auto format = static_cast<bool>(command.params.param2);
×
1131
    auto reset_image_log = static_cast<bool>(command.params.param3);
×
1132

1133
    UNUSED(format);
×
1134
    UNUSED(reset_image_log);
×
1135
    if (_format_storage_callbacks.empty()) {
×
1136
        LogDebug() << "process storage format requested with no storage format subscriber";
×
1137
        return _server_component_impl->make_command_ack_message(
×
1138
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1139
    }
1140

1141
    _last_format_storage_command = command;
×
1142
    _format_storage_callbacks(storage_id);
×
1143

1144
    return std::nullopt;
×
1145
}
1146

1147
std::optional<mavlink_command_ack_t> CameraServerImpl::process_camera_capture_status_request(
×
1148
    const MavlinkCommandReceiver::CommandLong& command)
1149
{
1150
    auto capture_status = static_cast<bool>(command.params.param1);
×
1151

1152
    if (!capture_status) {
×
1153
        return _server_component_impl->make_command_ack_message(
×
1154
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1155
    }
1156

1157
    if (_capture_status_callbacks.empty()) {
×
1158
        LogDebug() << "process camera capture status requested with no capture status subscriber";
×
1159
        return _server_component_impl->make_command_ack_message(
×
1160
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1161
    }
1162

1163
    _last_capture_status_command = command;
×
1164

1165
    // may not need param for now ,just use zero
1166
    _capture_status_callbacks(0);
×
1167

1168
    // ack was already sent
1169
    return std::nullopt;
×
1170
}
1171

1172
void CameraServerImpl::send_capture_status()
×
1173
{
1174
    uint8_t image_status{};
×
1175
    if (_capture_status.image_status ==
×
1176
            CameraServer::CaptureStatus::ImageStatus::CaptureInProgress ||
×
1177
        _capture_status.image_status ==
×
1178
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress) {
1179
        image_status |= StatusFlags::IN_PROGRESS;
×
1180
    }
1181

1182
    if (_capture_status.image_status == CameraServer::CaptureStatus::ImageStatus::IntervalIdle ||
×
1183
        _capture_status.image_status ==
×
1184
            CameraServer::CaptureStatus::ImageStatus::IntervalInProgress ||
×
1185
        _is_image_capture_interval_set) {
×
1186
        image_status |= StatusFlags::INTERVAL_SET;
×
1187
    }
1188

1189
    uint8_t video_status = 0;
×
1190
    if (_capture_status.video_status == CameraServer::CaptureStatus::VideoStatus::Idle) {
×
1191
        video_status = 0;
×
1192
    } else if (
×
1193
        _capture_status.video_status ==
×
1194
        CameraServer::CaptureStatus::VideoStatus::CaptureInProgress) {
1195
        video_status = 1;
×
1196
    }
1197

1198
    const uint32_t recording_time_ms =
×
1199
        static_cast<uint32_t>(static_cast<double>(_capture_status.recording_time_s) * 1e3);
×
1200
    const float available_capacity = _capture_status.available_capacity_mib;
×
1201

1202
    _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
1203
        mavlink_message_t message{};
×
1204
        mavlink_msg_camera_capture_status_pack_chan(
×
1205
            mavlink_address.system_id,
×
1206
            mavlink_address.component_id,
×
1207
            channel,
1208
            &message,
1209
            static_cast<uint32_t>(_server_component_impl->get_time().elapsed_s() * 1e3),
×
1210
            image_status,
×
1211
            video_status,
×
1212
            _image_capture_timer_interval_s,
1213
            recording_time_ms,
×
1214
            available_capacity,
×
1215
            _image_capture_count);
1216
        return message;
×
1217
    });
1218
}
×
1219

1220
std::optional<mavlink_command_ack_t>
1221
CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::CommandLong& command)
×
1222
{
1223
    auto reset = static_cast<bool>(command.params.param1);
×
1224

1225
    UNUSED(reset);
×
1226

1227
    if (_reset_settings_callbacks.empty()) {
×
1228
        LogDebug() << "reset camera settings requested with no camera settings subscriber";
×
1229
        return _server_component_impl->make_command_ack_message(
×
1230
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1231
    }
1232

1233
    _last_reset_settings_command = command;
×
1234
    _reset_settings_callbacks(0);
×
1235

1236
    return std::nullopt;
×
1237
}
1238

1239
std::optional<mavlink_command_ack_t>
1240
CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandLong& command)
×
1241
{
1242
    auto camera_mode = static_cast<CAMERA_MODE>(command.params.param2);
×
1243

1244
    if (_set_mode_callbacks.empty()) {
×
1245
        LogDebug() << "Set mode requested with no set mode subscriber";
×
1246
        return _server_component_impl->make_command_ack_message(
×
1247
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1248
    }
1249

1250
    // convert camera mode enum type
1251
    CameraServer::Mode convert_camera_mode = CameraServer::Mode::Unknown;
×
1252
    if (camera_mode == CAMERA_MODE_IMAGE) {
×
1253
        convert_camera_mode = CameraServer::Mode::Photo;
×
1254
    } else if (camera_mode == CAMERA_MODE_VIDEO) {
×
1255
        convert_camera_mode = CameraServer::Mode::Video;
×
1256
    }
1257

1258
    if (convert_camera_mode == CameraServer::Mode::Unknown) {
×
1259
        return _server_component_impl->make_command_ack_message(
×
1260
            command, MAV_RESULT::MAV_RESULT_DENIED);
×
1261
    }
1262

1263
    _last_set_mode_command = command;
×
1264
    _set_mode_callbacks(convert_camera_mode);
×
1265

1266
    return std::nullopt;
×
1267
}
1268

1269
std::optional<mavlink_command_ack_t>
1270
CameraServerImpl::process_set_camera_zoom(const MavlinkCommandReceiver::CommandLong& command)
×
1271
{
1272
    auto zoom_type = static_cast<CAMERA_ZOOM_TYPE>(command.params.param1);
×
1273
    auto zoom_value = command.params.param2;
×
1274

1275
    if (_zoom_in_start_callbacks.empty() && _zoom_out_start_callbacks.empty() &&
×
1276
        _zoom_stop_callbacks.empty() && _zoom_range_callbacks.empty()) {
×
1277
        LogWarn() << "No camera zoom is supported";
×
1278
        return _server_component_impl->make_command_ack_message(
×
1279
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1280
    }
1281

1282
    auto unsupported = [&]() {
×
1283
        LogWarn() << "unsupported set camera zoom type (" << (int)zoom_type << ") request";
×
1284
    };
×
1285

1286
    switch (zoom_type) {
×
1287
        case ZOOM_TYPE_CONTINUOUS:
×
1288
            if (zoom_value == -1.f) {
×
1289
                if (_zoom_out_start_callbacks.empty()) {
×
1290
                    unsupported();
×
1291
                    return _server_component_impl->make_command_ack_message(
×
1292
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1293
                } else {
1294
                    _last_zoom_out_start_command = command;
×
1295
                    int dummy = 0;
×
1296
                    _zoom_out_start_callbacks(dummy);
×
1297
                }
1298
            } else if (zoom_value == 1.f) {
×
1299
                if (_zoom_in_start_callbacks.empty()) {
×
1300
                    unsupported();
×
1301
                    return _server_component_impl->make_command_ack_message(
×
1302
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1303
                } else {
1304
                    _last_zoom_in_start_command = command;
×
1305
                    int dummy = 0;
×
1306
                    _zoom_in_start_callbacks(dummy);
×
1307
                }
1308
            } else if (zoom_value == 0.f) {
×
1309
                if (_zoom_stop_callbacks.empty()) {
×
1310
                    unsupported();
×
1311
                    return _server_component_impl->make_command_ack_message(
×
1312
                        command, MAV_RESULT::MAV_RESULT_DENIED);
×
1313
                } else {
1314
                    _last_zoom_stop_command = command;
×
1315
                    int dummy = 0;
×
1316
                    _zoom_stop_callbacks(dummy);
×
1317
                }
1318
            } else {
1319
                LogWarn() << "Invalid zoom value";
×
1320
                return _server_component_impl->make_command_ack_message(
×
1321
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1322
            }
1323
            break;
×
1324
        case ZOOM_TYPE_RANGE:
×
1325
            if (_zoom_range_callbacks.empty()) {
×
1326
                unsupported();
×
1327
                return _server_component_impl->make_command_ack_message(
×
1328
                    command, MAV_RESULT::MAV_RESULT_DENIED);
×
1329

1330
            } else {
1331
                _last_zoom_range_command = command;
×
1332
                _zoom_range_callbacks(zoom_value);
×
1333
            }
1334
            break;
×
1335
        case ZOOM_TYPE_STEP:
×
1336
        // Fallthrough
1337
        case ZOOM_TYPE_FOCAL_LENGTH:
1338
        // Fallthrough
1339
        case ZOOM_TYPE_HORIZONTAL_FOV:
1340
        // Fallthrough
1341
        default:
1342
            unsupported();
×
1343
            return _server_component_impl->make_command_ack_message(
×
1344
                command, MAV_RESULT::MAV_RESULT_DENIED);
×
1345
            break;
1346
    }
1347

1348
    // For any success so far, we don't ack yet, but later when the respond function is called.
1349
    return std::nullopt;
×
1350
}
1351

1352
std::optional<mavlink_command_ack_t>
1353
CameraServerImpl::process_set_camera_focus(const MavlinkCommandReceiver::CommandLong& command)
×
1354
{
1355
    auto focus_type = static_cast<SET_FOCUS_TYPE>(command.params.param1);
×
1356
    auto focus_value = command.params.param2;
×
1357

1358
    UNUSED(focus_type);
×
1359
    UNUSED(focus_value);
×
1360

1361
    LogDebug() << "unsupported set camera focus request";
×
1362

1363
    return _server_component_impl->make_command_ack_message(
×
1364
        command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1365
}
1366

1367
std::optional<mavlink_command_ack_t>
1368
CameraServerImpl::process_set_storage_usage(const MavlinkCommandReceiver::CommandLong& command)
×
1369
{
1370
    auto storage_id = static_cast<uint8_t>(command.params.param1);
×
1371
    auto usage = static_cast<STORAGE_USAGE_FLAG>(command.params.param2);
×
1372

1373
    UNUSED(storage_id);
×
1374
    UNUSED(usage);
×
1375

1376
    LogDebug() << "unsupported set storage usage request";
×
1377

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

1382
std::optional<mavlink_command_ack_t>
1383
CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1384
{
1385
    auto interval_s = command.params.param2;
×
1386
    auto total_images = static_cast<int32_t>(command.params.param3);
×
1387
    auto seq_number = static_cast<int32_t>(command.params.param4);
×
1388

1389
    LogDebug() << "received image start capture request - interval: " << +interval_s
×
1390
               << " total: " << +total_images << " index: " << +seq_number;
×
1391

1392
    // TODO: validate parameters and return MAV_RESULT_DENIED not valid
1393

1394
    stop_image_capture_interval();
×
1395

1396
    if (_take_photo_callbacks.empty()) {
×
1397
        LogDebug() << "image capture requested with no take photo subscriber";
×
1398
        return _server_component_impl->make_command_ack_message(
×
1399
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1400
    }
1401

1402
    // single image capture
1403
    if (total_images == 1) {
×
1404
        // MAV_RESULT_ACCEPTED must be sent before CAMERA_IMAGE_CAPTURED
1405
        auto command_ack = _server_component_impl->make_command_ack_message(
×
1406
            command, MAV_RESULT::MAV_RESULT_IN_PROGRESS);
×
1407
        _server_component_impl->send_command_ack(command_ack);
×
1408

1409
        _last_take_photo_command = command;
×
1410

1411
        _take_photo_callbacks(seq_number);
×
1412

1413
        return std::nullopt;
×
1414
    }
1415

1416
    start_image_capture_interval(interval_s, total_images, seq_number);
×
1417

1418
    return _server_component_impl->make_command_ack_message(
×
1419
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1420
}
1421

1422
std::optional<mavlink_command_ack_t>
1423
CameraServerImpl::process_image_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1424
{
1425
    LogDebug() << "received image stop capture request";
×
1426

1427
    // REVISIT: should we return something other that MAV_RESULT_ACCEPTED if
1428
    // there is not currently a capture interval active?
1429
    stop_image_capture_interval();
×
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> CameraServerImpl::process_camera_image_capture_request(
×
1436
    const MavlinkCommandReceiver::CommandLong& command)
1437
{
1438
    auto seq_number = static_cast<uint32_t>(command.params.param1);
×
1439

1440
    UNUSED(seq_number);
×
1441

1442
    LogDebug() << "unsupported image capture request";
×
1443

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

1448
std::optional<mavlink_command_ack_t>
1449
CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1450
{
1451
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1452
    auto status_frequency = command.params.param2;
×
1453

1454
    UNUSED(status_frequency);
×
1455

1456
    if (_start_video_callbacks.empty()) {
×
1457
        LogDebug() << "video start capture requested with no video start capture subscriber";
×
1458
        return _server_component_impl->make_command_ack_message(
×
1459
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1460
    }
1461

1462
    _last_start_video_command = command;
×
1463
    _start_video_callbacks(stream_id);
×
1464

1465
    return std::nullopt;
×
1466
}
1467

1468
std::optional<mavlink_command_ack_t>
1469
CameraServerImpl::process_video_stop_capture(const MavlinkCommandReceiver::CommandLong& command)
×
1470
{
1471
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1472

1473
    if (_stop_video_callbacks.empty()) {
×
1474
        LogDebug() << "video stop capture requested with no video stop capture subscriber";
×
1475
        return _server_component_impl->make_command_ack_message(
×
1476
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1477
    }
1478

1479
    _last_stop_video_command = command;
×
1480
    _stop_video_callbacks(stream_id);
×
1481

1482
    return std::nullopt;
×
1483
}
1484

1485
std::optional<mavlink_command_ack_t>
1486
CameraServerImpl::process_video_start_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1487
{
1488
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1489

1490
    if (_start_video_streaming_callbacks.empty()) {
×
1491
        LogDebug() << "video start streaming requested with no video start streaming subscriber";
×
1492
        return _server_component_impl->make_command_ack_message(
×
1493
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1494
    }
1495

1496
    _last_start_video_streaming_command = command;
×
1497
    _start_video_streaming_callbacks(stream_id);
×
1498

1499
    return std::nullopt;
×
1500
}
1501

1502
std::optional<mavlink_command_ack_t>
1503
CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::CommandLong& command)
×
1504
{
1505
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1506

1507
    if (_stop_video_streaming_callbacks.empty()) {
×
1508
        LogDebug() << "video stop streaming requested with no video stop streaming subscriber";
×
1509
        return _server_component_impl->make_command_ack_message(
×
1510
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1511
    }
1512

1513
    _last_stop_video_streaming_command = command;
×
1514
    _stop_video_streaming_callbacks(stream_id);
×
1515

1516
    return std::nullopt;
×
1517
}
1518

1519
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_information_request(
×
1520
    const MavlinkCommandReceiver::CommandLong& command)
1521
{
1522
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1523

1524
    UNUSED(stream_id);
×
1525

1526
    if (_is_video_streaming_set) {
×
1527
        auto command_ack = _server_component_impl->make_command_ack_message(
×
1528
            command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1529
        _server_component_impl->send_command_ack(command_ack);
×
1530
        LogDebug() << "sent video streaming ack";
×
1531

1532
        const char name[32] = "";
×
1533

1534
        _video_streaming.rtsp_uri.resize(sizeof(mavlink_video_stream_information_t::uri));
×
1535

1536
        mavlink_message_t msg{};
×
1537
        mavlink_msg_video_stream_information_pack(
×
1538
            _server_component_impl->get_own_system_id(),
×
1539
            _server_component_impl->get_own_component_id(),
×
1540
            &msg,
1541
            0, // Stream id
1542
            0, // Count
1543
            VIDEO_STREAM_TYPE_RTSP,
1544
            VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1545
            0, // famerate
1546
            0, // resolution horizontal
1547
            0, // resolution vertical
1548
            0, // bitrate
1549
            0, // rotation
1550
            0, // horizontal field of view
1551
            name,
1552
            _video_streaming.rtsp_uri.c_str());
1553

1554
        _server_component_impl->send_message(msg);
×
1555

1556
        // Ack already sent.
1557
        return std::nullopt;
×
1558

1559
    } else {
1560
        return _server_component_impl->make_command_ack_message(
×
1561
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1562
    }
1563
}
1564

1565
std::optional<mavlink_command_ack_t> CameraServerImpl::process_video_stream_status_request(
×
1566
    const MavlinkCommandReceiver::CommandLong& command)
1567
{
1568
    auto stream_id = static_cast<uint8_t>(command.params.param1);
×
1569

1570
    UNUSED(stream_id);
×
1571

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

1577
    auto command_ack =
×
1578
        _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1579
    _server_component_impl->send_command_ack(command_ack);
×
1580
    LogDebug() << "sent video streaming ack";
×
1581

1582
    mavlink_message_t msg{};
×
1583
    mavlink_msg_video_stream_status_pack(
×
1584
        _server_component_impl->get_own_system_id(),
×
1585
        _server_component_impl->get_own_component_id(),
×
1586
        &msg,
1587
        0, // Stream id
1588
        VIDEO_STREAM_STATUS_FLAGS_RUNNING,
1589
        0, // framerate
1590
        0, // resolution horizontal
1591
        0, // resolution vertical
1592
        0, // bitrate
1593
        0, // rotation
1594
        0 // horizontal field of view
1595
    );
1596
    _server_component_impl->send_message(msg);
×
1597

1598
    // ack was already sent
1599
    return std::nullopt;
×
1600
}
1601

1602
CameraServer::ZoomInStartHandle
1603
CameraServerImpl::subscribe_zoom_in_start(const CameraServer::ZoomInStartCallback& callback)
×
1604
{
1605
    return _zoom_in_start_callbacks.subscribe(callback);
×
1606
}
1607

1608
void CameraServerImpl::unsubscribe_zoom_in_start(CameraServer::ZoomInStartHandle handle)
×
1609
{
1610
    _zoom_in_start_callbacks.unsubscribe(handle);
×
1611
}
×
1612

1613
CameraServer::Result
1614
CameraServerImpl::respond_zoom_in_start(CameraServer::CameraFeedback zoom_in_start_feedback)
×
1615
{
1616
    switch (zoom_in_start_feedback) {
×
1617
        default:
×
1618
            // Fallthrough
1619
        case CameraServer::CameraFeedback::Unknown:
1620
            return CameraServer::Result::Error;
×
1621
        case CameraServer::CameraFeedback::Ok: {
×
1622
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1623
                _last_zoom_in_start_command, MAV_RESULT_ACCEPTED);
×
1624
            _server_component_impl->send_command_ack(command_ack);
×
1625
            return CameraServer::Result::Success;
×
1626
        }
1627
        case CameraServer::CameraFeedback::Busy: {
×
1628
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1629
                _last_zoom_in_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1630
            _server_component_impl->send_command_ack(command_ack);
×
1631
            return CameraServer::Result::Success;
×
1632
        }
1633
        case CameraServer::CameraFeedback::Failed: {
×
1634
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1635
                _last_zoom_in_start_command, MAV_RESULT_FAILED);
×
1636
            _server_component_impl->send_command_ack(command_ack);
×
1637
            return CameraServer::Result::Success;
×
1638
        }
1639
    }
1640
}
1641

1642
CameraServer::ZoomOutStartHandle
1643
CameraServerImpl::subscribe_zoom_out_start(const CameraServer::ZoomOutStartCallback& callback)
×
1644
{
1645
    return _zoom_out_start_callbacks.subscribe(callback);
×
1646
}
1647

1648
void CameraServerImpl::unsubscribe_zoom_out_start(CameraServer::ZoomOutStartHandle handle)
×
1649
{
1650
    _zoom_out_start_callbacks.unsubscribe(handle);
×
1651
}
×
1652

1653
CameraServer::Result
1654
CameraServerImpl::respond_zoom_out_start(CameraServer::CameraFeedback zoom_out_start_feedback)
×
1655
{
1656
    switch (zoom_out_start_feedback) {
×
1657
        default:
×
1658
            // Fallthrough
1659
        case CameraServer::CameraFeedback::Unknown:
1660
            return CameraServer::Result::Error;
×
1661
        case CameraServer::CameraFeedback::Ok: {
×
1662
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1663
                _last_zoom_out_start_command, MAV_RESULT_ACCEPTED);
×
1664
            _server_component_impl->send_command_ack(command_ack);
×
1665
            return CameraServer::Result::Success;
×
1666
        }
1667
        case CameraServer::CameraFeedback::Busy: {
×
1668
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1669
                _last_zoom_out_start_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1670
            _server_component_impl->send_command_ack(command_ack);
×
1671
            return CameraServer::Result::Success;
×
1672
        }
1673
        case CameraServer::CameraFeedback::Failed: {
×
1674
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1675
                _last_zoom_out_start_command, MAV_RESULT_FAILED);
×
1676
            _server_component_impl->send_command_ack(command_ack);
×
1677
            return CameraServer::Result::Success;
×
1678
        }
1679
    }
1680
}
1681

1682
CameraServer::ZoomStopHandle
1683
CameraServerImpl::subscribe_zoom_stop(const CameraServer::ZoomStopCallback& callback)
×
1684
{
1685
    return _zoom_stop_callbacks.subscribe(callback);
×
1686
}
1687

1688
void CameraServerImpl::unsubscribe_zoom_stop(CameraServer::ZoomStopHandle handle)
×
1689
{
1690
    _zoom_stop_callbacks.unsubscribe(handle);
×
1691
}
×
1692

1693
CameraServer::Result
1694
CameraServerImpl::respond_zoom_stop(CameraServer::CameraFeedback zoom_stop_feedback)
×
1695
{
1696
    switch (zoom_stop_feedback) {
×
1697
        default:
×
1698
            // Fallthrough
1699
        case CameraServer::CameraFeedback::Unknown:
1700
            return CameraServer::Result::Error;
×
1701
        case CameraServer::CameraFeedback::Ok: {
×
1702
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1703
                _last_zoom_stop_command, MAV_RESULT_ACCEPTED);
×
1704
            _server_component_impl->send_command_ack(command_ack);
×
1705
            return CameraServer::Result::Success;
×
1706
        }
1707
        case CameraServer::CameraFeedback::Busy: {
×
1708
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1709
                _last_zoom_stop_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1710
            _server_component_impl->send_command_ack(command_ack);
×
1711
            return CameraServer::Result::Success;
×
1712
        }
1713
        case CameraServer::CameraFeedback::Failed: {
×
1714
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1715
                _last_zoom_stop_command, MAV_RESULT_FAILED);
×
1716
            _server_component_impl->send_command_ack(command_ack);
×
1717
            return CameraServer::Result::Success;
×
1718
        }
1719
    }
1720
}
1721

1722
CameraServer::ZoomRangeHandle
1723
CameraServerImpl::subscribe_zoom_range(const CameraServer::ZoomRangeCallback& callback)
×
1724
{
1725
    return _zoom_range_callbacks.subscribe(callback);
×
1726
}
1727

1728
void CameraServerImpl::unsubscribe_zoom_range(CameraServer::ZoomRangeHandle handle)
×
1729
{
1730
    _zoom_range_callbacks.unsubscribe(handle);
×
1731
}
×
1732

1733
CameraServer::Result
1734
CameraServerImpl::respond_zoom_range(CameraServer::CameraFeedback zoom_range_feedback)
×
1735
{
1736
    switch (zoom_range_feedback) {
×
1737
        case CameraServer::CameraFeedback::Ok: {
×
1738
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1739
                _last_zoom_range_command, MAV_RESULT_ACCEPTED);
×
1740
            _server_component_impl->send_command_ack(command_ack);
×
1741
            return CameraServer::Result::Success;
×
1742
        }
1743
        case CameraServer::CameraFeedback::Busy: {
×
1744
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1745
                _last_zoom_range_command, MAV_RESULT_TEMPORARILY_REJECTED);
×
1746
            _server_component_impl->send_command_ack(command_ack);
×
1747
            return CameraServer::Result::Success;
×
1748
        }
1749
        case CameraServer::CameraFeedback::Failed: {
×
1750
            auto command_ack = _server_component_impl->make_command_ack_message(
×
1751
                _last_zoom_range_command, MAV_RESULT_FAILED);
×
1752
            _server_component_impl->send_command_ack(command_ack);
×
1753
            return CameraServer::Result::Success;
×
1754
        }
1755
        case CameraServer::CameraFeedback::Unknown:
×
1756
            // Fallthrough
1757
        default:
1758
            return CameraServer::Result::Error;
×
1759
    }
1760
}
1761

1762
std::optional<mavlink_command_ack_t>
1763
CameraServerImpl::process_track_point_command(const MavlinkCommandReceiver::CommandLong& command)
×
1764
{
1765
    if (!is_command_sender_ok(command)) {
×
1766
        LogWarn() << "Incoming track point command is for target sysid "
×
1767
                  << int(command.target_system_id) << " instead of "
×
1768
                  << int(_server_component_impl->get_own_system_id());
×
1769
        return std::nullopt;
×
1770
    }
1771

1772
    if (_tracking_point_callbacks.empty()) {
×
1773
        LogDebug() << "Track point requested with no user callback provided";
×
1774
        return _server_component_impl->make_command_ack_message(
×
1775
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1776
    }
1777

1778
    CameraServer::TrackPoint track_point{
×
1779
        command.params.param1, command.params.param2, command.params.param3};
×
1780

1781
    _last_track_point_command = command;
×
1782
    _tracking_point_callbacks(track_point);
×
1783
    // We don't send an ack but leave that to the user.
1784
    return std::nullopt;
×
1785
}
1786

1787
std::optional<mavlink_command_ack_t> CameraServerImpl::process_track_rectangle_command(
×
1788
    const MavlinkCommandReceiver::CommandLong& command)
1789
{
1790
    if (!is_command_sender_ok(command)) {
×
1791
        LogWarn() << "Incoming track rectangle command is for target sysid "
×
1792
                  << int(command.target_system_id) << " instead of "
×
1793
                  << int(_server_component_impl->get_own_system_id());
×
1794
        return std::nullopt;
×
1795
    }
1796

1797
    if (_tracking_rectangle_callbacks.empty()) {
×
1798
        LogDebug() << "Track rectangle requested with no user callback provided";
×
1799
        return _server_component_impl->make_command_ack_message(
×
1800
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1801
    }
1802

1803
    CameraServer::TrackRectangle track_rectangle{
×
1804
        command.params.param1, command.params.param2, command.params.param3, command.params.param4};
×
1805

1806
    _last_track_rectangle_command = command;
×
1807
    _tracking_rectangle_callbacks(track_rectangle);
×
1808
    // We don't send an ack but leave that to the user.
1809
    return std::nullopt;
×
1810
}
1811

1812
std::optional<mavlink_command_ack_t>
1813
CameraServerImpl::process_track_off_command(const MavlinkCommandReceiver::CommandLong& command)
×
1814
{
1815
    if (!is_command_sender_ok(command)) {
×
1816
        LogWarn() << "Incoming track off command is for target sysid "
×
1817
                  << int(command.target_system_id) << " instead of "
×
1818
                  << int(_server_component_impl->get_own_system_id());
×
1819
        return std::nullopt;
×
1820
    }
1821

1822
    if (_tracking_off_callbacks.empty()) {
×
1823
        LogDebug() << "Tracking off requested with no user callback provided";
×
1824
        return _server_component_impl->make_command_ack_message(
×
1825
            command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
×
1826
    }
1827

1828
    _last_tracking_off_command = command;
×
1829
    _tracking_off_callbacks(0);
×
1830
    // We don't send an ack but leave that to the user.
1831
    return std::nullopt;
×
1832
}
1833

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

1844
    auto message_id = static_cast<uint32_t>(command.params.param1);
×
1845
    auto interval_us = static_cast<int32_t>(command.params.param2);
×
1846
    UNUSED(message_id);
×
1847

1848
    // Interval value of -1 means to disable sending messages
1849
    if (interval_us < 0) {
×
1850
        stop_sending_tracking_status();
×
1851
    } else {
1852
        start_sending_tracking_status(interval_us);
×
1853
    }
1854

1855
    // Always send the "Accepted" result
1856
    return _server_component_impl->make_command_ack_message(
×
1857
        command, MAV_RESULT::MAV_RESULT_ACCEPTED);
×
1858
}
1859

1860
void CameraServerImpl::send_tracking_status_with_interval(uint32_t interval_us)
×
1861
{
1862
    while (true) {
1863
        std::this_thread::sleep_for(std::chrono::microseconds{interval_us});
×
1864
        {
1865
            std::scoped_lock lg{_tracking_status_mutex};
×
1866
            if (!_sending_tracking_status) {
×
1867
                return;
×
1868
            }
1869
        }
1870
        _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
1871
            mavlink_message_t message;
1872
            std::lock_guard<std::mutex> lg{_tracking_status_mutex};
×
1873

1874
            // The message is filled based on current tracking mode
1875
            switch (_tracking_mode) {
×
1876
                default:
×
1877
                    // Fallthrough
1878
                case TrackingMode::NONE:
1879

1880
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
1881
                        mavlink_address.system_id,
×
1882
                        mavlink_address.component_id,
×
1883
                        channel,
1884
                        &message,
1885
                        CAMERA_TRACKING_STATUS_FLAGS_IDLE,
1886
                        CAMERA_TRACKING_MODE_NONE,
1887
                        CAMERA_TRACKING_TARGET_DATA_NONE,
1888
                        0.0f,
1889
                        0.0f,
1890
                        0.0f,
1891
                        0.0f,
1892
                        0.0f,
1893
                        0.0f,
1894
                        0.0f);
1895
                    break;
×
1896
                case TrackingMode::POINT:
×
1897

1898
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
1899
                        mavlink_address.system_id,
×
1900
                        mavlink_address.component_id,
×
1901
                        channel,
1902
                        &message,
1903
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
1904
                        CAMERA_TRACKING_MODE_POINT,
1905
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
1906
                        _tracked_point.point_x,
1907
                        _tracked_point.point_y,
1908
                        _tracked_point.radius,
1909
                        0.0f,
1910
                        0.0f,
1911
                        0.0f,
1912
                        0.0f);
1913
                    break;
×
1914

1915
                case TrackingMode::RECTANGLE:
×
1916

1917
                    mavlink_msg_camera_tracking_image_status_pack_chan(
×
1918
                        mavlink_address.system_id,
×
1919
                        mavlink_address.component_id,
×
1920
                        channel,
1921
                        &message,
1922
                        CAMERA_TRACKING_STATUS_FLAGS_ACTIVE,
1923
                        CAMERA_TRACKING_MODE_RECTANGLE,
1924
                        CAMERA_TRACKING_TARGET_DATA_IN_STATUS,
1925
                        0.0f,
1926
                        0.0f,
1927
                        0.0f,
1928
                        _tracked_rectangle.top_left_corner_x,
1929
                        _tracked_rectangle.top_left_corner_y,
1930
                        _tracked_rectangle.bottom_right_corner_x,
1931
                        _tracked_rectangle.bottom_right_corner_y);
1932
                    break;
×
1933
            }
1934
            return message;
×
1935
        });
1936
    }
×
1937
}
1938

1939
void CameraServerImpl::start_sending_tracking_status(uint32_t interval_ms)
×
1940
{
1941
    // Stop sending status with the old interval
1942
    stop_sending_tracking_status();
×
1943
    _sending_tracking_status = true;
×
1944
    _tracking_status_sending_thread =
×
1945
        std::thread{&CameraServerImpl::send_tracking_status_with_interval, this, interval_ms};
×
1946
}
×
1947

1948
void CameraServerImpl::stop_sending_tracking_status()
×
1949
{
1950
    // Firstly, ask the other thread to stop sending the status
1951
    {
1952
        std::scoped_lock lg{_tracking_status_mutex};
×
1953
        _sending_tracking_status = false;
×
1954
    }
1955
    // If the thread was active, wait for it to finish
1956
    if (_tracking_status_sending_thread.joinable()) {
×
1957
        _tracking_status_sending_thread.join();
×
1958
    }
1959
}
×
1960

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