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

mavlink / MAVSDK / 6568658631

19 Oct 2023 01:31AM UTC coverage: 31.23% (+0.02%) from 31.215%
6568658631

push

github

web-flow
Merge pull request #2155 from mavlink/pr-static-fixes

Threading fixes, MAVLink sequence number cleanup

1386 of 1386 new or added lines in 46 files covered. (100.0%)

7906 of 25315 relevant lines covered (31.23%)

23.54 hits per line

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

40.34
/src/mavsdk/core/system_impl.cpp
1
#include "system.h"
2
#include "mavsdk_impl.h"
3
#include "mavlink_include.h"
4
#include "system_impl.h"
5
#include "server_component_impl.h"
6
#include "plugin_impl_base.h"
7
#include "px4_custom_mode.h"
8
#include "ardupilot_custom_mode.h"
9
#include "request_message.h"
10
#include "callback_list.tpp"
11
#include "unused.h"
12
#include <cassert>
13
#include <cstdlib>
14
#include <functional>
15
#include <future>
16
#include <utility>
17

18
namespace mavsdk {
19

20
template class CallbackList<bool>;
21
template class CallbackList<System::ComponentType>;
22
template class CallbackList<System::ComponentType, uint8_t>;
23

24
SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) :
20✔
25
    _mavsdk_impl(mavsdk_impl),
26
    _command_sender(*this),
27
    _timesync(*this),
28
    _ping(*this),
29
    _mission_transfer(
30
        _mavsdk_impl.default_server_component_impl().sender(),
20✔
31
        _mavsdk_impl.mavlink_message_handler,
20✔
32
        _mavsdk_impl.timeout_handler,
20✔
33
        [this]() { return timeout_s(); }),
1✔
34
    _request_message(
35
        *this, _command_sender, _mavsdk_impl.mavlink_message_handler, _mavsdk_impl.timeout_handler),
20✔
36
    _mavlink_ftp(*this)
40✔
37
{
38
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
20✔
39
}
20✔
40

41
SystemImpl::~SystemImpl()
20✔
42
{
43
    _should_exit = true;
20✔
44
    _mavsdk_impl.mavlink_message_handler.unregister_all(this);
20✔
45

46
    unregister_timeout_handler(_heartbeat_timeout_cookie);
20✔
47

48
    if (_system_thread != nullptr) {
20✔
49
        _system_thread->join();
20✔
50
        delete _system_thread;
20✔
51
        _system_thread = nullptr;
20✔
52
    }
53
}
20✔
54

55
void SystemImpl::init(uint8_t system_id, uint8_t comp_id)
20✔
56
{
57
    _target_address.system_id = system_id;
20✔
58
    // We use this as a default.
59
    _target_address.component_id = MAV_COMP_ID_AUTOPILOT1;
20✔
60

61
    _mavsdk_impl.mavlink_message_handler.register_one(
20✔
62
        MAVLINK_MSG_ID_HEARTBEAT,
63
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
20✔
64
        this);
65

66
    _mavsdk_impl.mavlink_message_handler.register_one(
20✔
67
        MAVLINK_MSG_ID_STATUSTEXT,
68
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
69
        this);
70

71
    _mavsdk_impl.mavlink_message_handler.register_one(
20✔
72
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
73
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
12✔
74
        this);
75

76
    // register_mavlink_command_handler(
77
    //    MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
78
    //    [this](const MavlinkCommandReceiver::CommandLong& command) {
79
    //        return process_autopilot_version_request(command);
80
    //    },
81
    //    this);
82

83
    //// TO-DO!
84
    // register_mavlink_command_handler(
85
    //    MAV_CMD_REQUEST_MESSAGE,
86
    //    [this](const MavlinkCommandReceiver::CommandLong& command) {
87
    //        return make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
88
    //    },
89
    //    this);
90

91
    add_new_component(comp_id);
20✔
92
}
20✔
93

94
bool SystemImpl::is_connected() const
12✔
95
{
96
    return _connected;
12✔
97
}
98

99
void SystemImpl::register_mavlink_message_handler(
89✔
100
    uint16_t msg_id, const MavlinkMessageHandler& callback, const void* cookie)
101
{
102
    _mavsdk_impl.mavlink_message_handler.register_one(msg_id, callback, cookie);
89✔
103
}
89✔
104

105
void SystemImpl::register_mavlink_message_handler(
7✔
106
    uint16_t msg_id, uint8_t cmp_id, const MavlinkMessageHandler& callback, const void* cookie)
107
{
108
    _mavsdk_impl.mavlink_message_handler.register_one(msg_id, cmp_id, callback, cookie);
7✔
109
}
7✔
110

111
void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
112
{
113
    _mavsdk_impl.mavlink_message_handler.unregister_one(msg_id, cookie);
×
114
}
×
115

116
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
64✔
117
{
118
    _mavsdk_impl.mavlink_message_handler.unregister_all(cookie);
64✔
119
}
64✔
120

121
void SystemImpl::update_componentid_messages_handler(
×
122
    uint16_t msg_id, uint8_t cmp_id, const void* cookie)
123
{
124
    _mavsdk_impl.mavlink_message_handler.update_component_id(msg_id, cmp_id, cookie);
×
125
}
×
126

127
void SystemImpl::register_timeout_handler(
35✔
128
    const std::function<void()>& callback, double duration_s, void** cookie)
129
{
130
    _mavsdk_impl.timeout_handler.add(callback, duration_s, cookie);
35✔
131
}
35✔
132

133
void SystemImpl::refresh_timeout_handler(const void* cookie)
2✔
134
{
135
    _mavsdk_impl.timeout_handler.refresh(cookie);
2✔
136
}
2✔
137

138
void SystemImpl::unregister_timeout_handler(const void* cookie)
34✔
139
{
140
    _mavsdk_impl.timeout_handler.remove(cookie);
34✔
141
}
34✔
142

143
double SystemImpl::timeout_s() const
58✔
144
{
145
    return _mavsdk_impl.timeout_s();
58✔
146
}
147

148
void SystemImpl::enable_timesync()
×
149
{
150
    _timesync.enable();
×
151
}
×
152

153
System::IsConnectedHandle
154
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
155
{
156
    std::lock_guard<std::mutex> lock(_connection_mutex);
×
157
    return _is_connected_callbacks.subscribe(callback);
×
158
}
159

160
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
161
{
162
    _is_connected_callbacks.unsubscribe(handle);
×
163
}
×
164

165
void SystemImpl::add_call_every(std::function<void()> callback, float interval_s, void** cookie)
4✔
166
{
167
    _mavsdk_impl.call_every_handler.add(
8✔
168
        std::move(callback), static_cast<double>(interval_s), cookie);
4✔
169
}
4✔
170

171
void SystemImpl::change_call_every(float interval_s, const void* cookie)
×
172
{
173
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
174
}
×
175

176
void SystemImpl::reset_call_every(const void* cookie)
×
177
{
178
    _mavsdk_impl.call_every_handler.reset(cookie);
×
179
}
×
180

181
void SystemImpl::remove_call_every(const void* cookie)
10✔
182
{
183
    _mavsdk_impl.call_every_handler.remove(cookie);
10✔
184
}
10✔
185

186
void SystemImpl::register_statustext_handler(
1✔
187
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
188
{
189
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
190
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
1✔
191
}
1✔
192

193
void SystemImpl::unregister_statustext_handler(void* cookie)
1✔
194
{
195
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
196
    _statustext_handler_callbacks.erase(std::remove_if(
1✔
197
        _statustext_handler_callbacks.begin(),
198
        _statustext_handler_callbacks.end(),
199
        [&](const auto& entry) { return entry.cookie == cookie; }));
2✔
200
}
1✔
201

202
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
20✔
203
{
204
    mavlink_heartbeat_t heartbeat;
20✔
205
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
20✔
206

207
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
20✔
208
        _autopilot = Autopilot::Px4;
×
209
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
20✔
210
        _autopilot = Autopilot::ArduPilot;
×
211
    }
212

213
    // Only set the vehicle type if the heartbeat is from an autopilot component
214
    // This check only works if the MAV_TYPE::MAV_TYPE_ENUM_END is actually the
215
    // last enumerator.
216
    if (MAV_TYPE::MAV_TYPE_ENUM_END < heartbeat.type) {
20✔
217
        LogErr() << "type received in HEARTBEAT was not recognized";
×
218
    } else {
219
        const auto new_vehicle_type = static_cast<MAV_TYPE>(heartbeat.type);
20✔
220
        if (heartbeat.autopilot != MAV_AUTOPILOT_INVALID && _vehicle_type != new_vehicle_type &&
20✔
221
            new_vehicle_type != MAV_TYPE_GENERIC) {
222
            LogWarn() << "Vehicle type changed (new type: " << static_cast<unsigned>(heartbeat.type)
×
223
                      << ", old type: " << static_cast<unsigned>(_vehicle_type) << ")";
×
224
            _vehicle_type = new_vehicle_type;
×
225
        }
226
    }
227

228
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
20✔
229
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
10✔
230
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
10✔
231
    }
232
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
20✔
233
        _flight_mode =
×
234
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
235
    }
236

237
    set_connected();
20✔
238
}
20✔
239

240
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
241
{
242
    mavlink_statustext_t statustext;
3✔
243
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
244

245
    const auto maybe_result = _statustext_handler.process(statustext);
6✔
246

247
    if (maybe_result.has_value()) {
3✔
248
        LogDebug() << "MAVLink: "
6✔
249
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
250
                   << maybe_result.value().text;
9✔
251

252
        std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
6✔
253
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
254
            entry.callback(maybe_result.value());
3✔
255
        }
256
    }
257
}
3✔
258

259
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
12✔
260
{
261
    mavlink_autopilot_version_t autopilot_version;
12✔
262
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
12✔
263

264
    _mission_transfer.set_int_messages_supported(
12✔
265
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
12✔
266
}
12✔
267

268
void SystemImpl::heartbeats_timed_out()
×
269
{
270
    LogInfo() << "heartbeats timed out";
×
271
    set_disconnected();
×
272
}
×
273

274
void SystemImpl::system_thread()
20✔
275
{
276
    SteadyTimePoint last_ping_time{};
20✔
277

278
    while (!_should_exit) {
624✔
279
        {
280
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
1,208✔
281
            for (auto& entry : _mavlink_parameter_clients) {
908✔
282
                entry.parameter_client->do_work();
304✔
283
            }
284
        }
285
        _command_sender.do_work();
604✔
286
        _timesync.do_work();
604✔
287
        _mission_transfer.do_work();
604✔
288

289
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
604✔
290
            if (_connected && _autopilot != Autopilot::ArduPilot) {
20✔
291
                _ping.run_once();
×
292
            }
293
            last_ping_time = _mavsdk_impl.time.steady_time();
20✔
294
        }
295

296
        if (_connected) {
604✔
297
            // Work fairly fast if we're connected.
298
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
554✔
299
        } else {
300
            // Be less aggressive when unconnected.
301
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
50✔
302
        }
303
    }
304
}
20✔
305

306
// std::optional<mavlink_message_t>
307
// SystemImpl::process_autopilot_version_request(const MavlinkCommandReceiver::CommandLong& command)
308
//{
309
//    if (_should_send_autopilot_version) {
310
//        send_autopilot_version();
311
//        return make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
312
//    }
313
//
314
//    return {};
315
//}
316

317
std::string SystemImpl::component_name(uint8_t component_id)
20✔
318
{
319
    switch (component_id) {
20✔
320
        case MAV_COMP_ID_AUTOPILOT1:
9✔
321
            return "Autopilot";
9✔
322
        case MAV_COMP_ID_CAMERA:
1✔
323
            return "Camera 1";
1✔
324
        case MAV_COMP_ID_CAMERA2:
×
325
            return "Camera 2";
×
326
        case MAV_COMP_ID_CAMERA3:
×
327
            return "Camera 3";
×
328
        case MAV_COMP_ID_CAMERA4:
×
329
            return "Camera 4";
×
330
        case MAV_COMP_ID_CAMERA5:
×
331
            return "Camera 5";
×
332
        case MAV_COMP_ID_CAMERA6:
×
333
            return "Camera 6";
×
334
        case MAV_COMP_ID_GIMBAL:
×
335
            return "Gimbal";
×
336
        case MAV_COMP_ID_MISSIONPLANNER:
10✔
337
            return "Ground station";
10✔
338
        case MAV_COMP_ID_WINCH:
×
339
            return "Winch";
×
340
        default:
×
341
            return "Unsupported component";
×
342
    }
343
}
344

345
System::ComponentType SystemImpl::component_type(uint8_t component_id)
40✔
346
{
347
    switch (component_id) {
40✔
348
        case MAV_COMP_ID_AUTOPILOT1:
18✔
349
            return System::ComponentType::AUTOPILOT;
18✔
350
        case MAV_COMP_ID_CAMERA:
2✔
351
        case MAV_COMP_ID_CAMERA2:
352
        case MAV_COMP_ID_CAMERA3:
353
        case MAV_COMP_ID_CAMERA4:
354
        case MAV_COMP_ID_CAMERA5:
355
        case MAV_COMP_ID_CAMERA6:
356
            return System::ComponentType::CAMERA;
2✔
357
        case MAV_COMP_ID_GIMBAL:
×
358
            return System::ComponentType::GIMBAL;
×
359
        default:
20✔
360
            return System::ComponentType::UNKNOWN;
20✔
361
    }
362
}
363

364
void SystemImpl::add_new_component(uint8_t component_id)
180✔
365
{
366
    if (component_id == 0) {
180✔
367
        return;
10✔
368
    }
369

370
    auto res_pair = _components.insert(component_id);
170✔
371
    if (res_pair.second) {
170✔
372
        std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
40✔
373
        _component_discovered_callbacks.queue(
20✔
374
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
375
        _component_discovered_id_callbacks.queue(
20✔
376
            component_type(component_id), component_id, [this](const auto& func) {
×
377
                call_user_callback(func);
×
378
            });
×
379
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
80✔
380
                   << ") added.";
80✔
381
    }
382
}
383

384
size_t SystemImpl::total_components() const
×
385
{
386
    return _components.size();
×
387
}
388

389
System::ComponentDiscoveredHandle
390
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
391
{
392
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
393
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
394

395
    if (total_components() > 0) {
×
396
        for (const auto& elem : _components) {
×
397
            _component_discovered_callbacks.queue(
×
398
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
399
        }
400
    }
401
    return handle;
×
402
}
403

404
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
405
{
406
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
407
    _component_discovered_callbacks.unsubscribe(handle);
×
408
}
×
409

410
System::ComponentDiscoveredIdHandle
411
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
412
{
413
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
414
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
415

416
    if (total_components() > 0) {
×
417
        for (const auto& elem : _components) {
×
418
            _component_discovered_id_callbacks.queue(
×
419
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
420
        }
421
    }
422
    return handle;
×
423
}
424

425
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
426
{
427
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
428
    _component_discovered_id_callbacks.unsubscribe(handle);
×
429
}
×
430

431
bool SystemImpl::is_standalone() const
×
432
{
433
    return !has_autopilot();
×
434
}
435

436
bool SystemImpl::has_autopilot() const
37✔
437
{
438
    return get_autopilot_id() != uint8_t(0);
37✔
439
}
440

441
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
442
{
443
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
444
}
445

446
bool SystemImpl::is_camera(uint8_t comp_id)
1✔
447
{
448
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
1✔
449
}
450

451
bool SystemImpl::has_camera(int camera_id) const
1✔
452
{
453
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
1✔
454

455
    if (camera_comp_id == -1) { // Check whether the system has any camera.
1✔
456
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
1✔
457
            return true;
1✔
458
        }
459
    } else { // Look for the camera whose id is `camera_id`.
460
        for (auto compid : _components) {
×
461
            if (compid == camera_comp_id) {
×
462
                return true;
×
463
            }
464
        }
465
    }
466
    return false;
×
467
}
468

469
bool SystemImpl::has_gimbal() const
×
470
{
471
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
472
}
473

474
bool SystemImpl::send_message(mavlink_message_t& message)
×
475
{
476
    return _mavsdk_impl.send_message(message);
×
477
}
478

479
bool SystemImpl::queue_message(
15✔
480
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
481
{
482
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
15✔
483
}
484

485
void SystemImpl::send_autopilot_version_request()
×
486
{
487
    auto prom = std::promise<MavlinkCommandSender::Result>();
×
488
    auto fut = prom.get_future();
×
489

490
    send_autopilot_version_request_async(
×
491
        [&prom](MavlinkCommandSender::Result result, float) { prom.set_value(result); });
×
492

493
    if (fut.get() == MavlinkCommandSender::Result::Unsupported) {
×
494
        _old_message_520_supported = false;
×
495
        LogWarn() << "Trying alternative command (512).";
×
496
        send_autopilot_version_request();
×
497
    }
498
}
×
499

500
void SystemImpl::send_autopilot_version_request_async(
9✔
501
    const MavlinkCommandSender::CommandResultCallback& callback)
502
{
503
    MavlinkCommandSender::CommandLong command{};
9✔
504
    command.target_component_id = get_autopilot_id();
9✔
505

506
    if (_old_message_520_supported) {
9✔
507
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
508
        // release.
509
        command.command = MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES;
9✔
510
        command.params.maybe_param1 = 1.0f;
9✔
511
    } else {
512
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
513
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_AUTOPILOT_VERSION)};
×
514
    }
515

516
    send_command_async(command, callback);
9✔
517
}
9✔
518

519
void SystemImpl::send_flight_information_request()
×
520
{
521
    auto prom = std::promise<MavlinkCommandSender::Result>();
×
522
    auto fut = prom.get_future();
×
523

524
    MavlinkCommandSender::CommandLong command{};
×
525
    command.target_component_id = get_autopilot_id();
×
526

527
    if (_old_message_528_supported) {
×
528
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
529
        // release.
530
        command.command = MAV_CMD_REQUEST_FLIGHT_INFORMATION;
×
531
        command.params.maybe_param1 = 1.0f;
×
532
    } else {
533
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
534
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_FLIGHT_INFORMATION)};
×
535
    }
536

537
    send_command_async(
×
538
        command, [&prom](MavlinkCommandSender::Result result, float) { prom.set_value(result); });
×
539
    if (fut.get() == MavlinkCommandSender::Result::Unsupported) {
×
540
        _old_message_528_supported = false;
×
541
        LogWarn() << "Trying alternative command (512)..";
×
542
        send_flight_information_request();
×
543
    }
544
}
×
545

546
void SystemImpl::set_connected()
20✔
547
{
548
    bool enable_needed = false;
20✔
549
    {
550
        std::lock_guard<std::mutex> lock(_connection_mutex);
40✔
551

552
        if (!_connected) {
20✔
553
            if (!_components.empty()) {
18✔
554
                LogDebug() << "Discovered " << _components.size() << " component(s)";
18✔
555
            }
556

557
            _connected = true;
18✔
558

559
            // System with sysid 0 is a bit special: it is a placeholder for a connection initiated
560
            // by MAVSDK. As such, it should not be advertised as a newly discovered system.
561
            if (static_cast<int>(get_system_id()) != 0) {
18✔
562
                _mavsdk_impl.notify_on_discover();
18✔
563
            }
564

565
            // We call this later to avoid deadlocks on creating the server components.
566
            _mavsdk_impl.call_user_callback([this]() {
36✔
567
                // Send a heartbeat back immediately.
568
                _mavsdk_impl.start_sending_heartbeats();
569
            });
570

571
            register_timeout_handler(
18✔
572
                [this] { heartbeats_timed_out(); },
×
573
                HEARTBEAT_TIMEOUT_S,
574
                &_heartbeat_timeout_cookie);
575

576
            enable_needed = true;
18✔
577

578
            _is_connected_callbacks.queue(
18✔
579
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
580

581
        } else if (_connected) {
2✔
582
            refresh_timeout_handler(_heartbeat_timeout_cookie);
2✔
583
        }
584
        // If not yet connected there is nothing to do/
585
    }
586
    if (enable_needed) {
20✔
587
        if (has_autopilot()) {
18✔
588
            send_autopilot_version_request_async(nullptr);
9✔
589
        }
590

591
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
36✔
592
        for (auto plugin_impl : _plugin_impls) {
18✔
593
            plugin_impl->enable();
×
594
        }
595
    }
596
}
20✔
597

598
void SystemImpl::set_disconnected()
×
599
{
600
    {
601
        std::lock_guard<std::mutex> lock(_connection_mutex);
×
602

603
        // This might not be needed because this is probably called from the triggered
604
        // timeout anyway, but it should also do no harm.
605
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
606
        //_heartbeat_timeout_cookie = nullptr;
607

608
        _connected = false;
×
609
        _mavsdk_impl.notify_on_timeout();
×
610
        _is_connected_callbacks.queue(
×
611
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
612
    }
613

614
    _mavsdk_impl.stop_sending_heartbeats();
×
615

616
    {
617
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
618
        for (auto plugin_impl : _plugin_impls) {
×
619
            plugin_impl->disable();
×
620
        }
621
    }
622
}
×
623

624
uint8_t SystemImpl::get_system_id() const
41✔
625
{
626
    return _target_address.system_id;
41✔
627
}
628

629
std::vector<uint8_t> SystemImpl::component_ids() const
×
630
{
631
    return std::vector<uint8_t>{_components.begin(), _components.end()};
×
632
}
633

634
void SystemImpl::set_system_id(uint8_t system_id)
10✔
635
{
636
    _target_address.system_id = system_id;
10✔
637
}
10✔
638

639
uint8_t SystemImpl::get_own_system_id() const
12✔
640
{
641
    return _mavsdk_impl.get_own_system_id();
12✔
642
}
643

644
uint8_t SystemImpl::get_own_component_id() const
12✔
645
{
646
    return _mavsdk_impl.get_own_component_id();
12✔
647
}
648

649
MAV_TYPE SystemImpl::get_vehicle_type() const
×
650
{
651
    return _vehicle_type;
×
652
}
653

654
uint8_t SystemImpl::get_own_mav_type() const
×
655
{
656
    return _mavsdk_impl.get_mav_type();
×
657
}
658

659
MavlinkParameterClient::Result SystemImpl::set_param(
×
660
    const std::string& name,
661
    ParamValue value,
662
    std::optional<uint8_t> maybe_component_id,
663
    bool extended)
664
{
665
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
666
        ->set_param(name, value);
×
667
}
668

669
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
670
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
671
{
672
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
673
        ->set_param_float(name, value);
4✔
674
}
675

676
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
677
    const std::string& name,
678
    int32_t value,
679
    std::optional<uint8_t> maybe_component_id,
680
    bool extended)
681
{
682
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
683
        ->set_param_int(name, value);
4✔
684
}
685

686
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
687
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
688
{
689
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
690
        ->set_param_custom(name, value);
4✔
691
}
692

693
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
694
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
695
{
696
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
697
        ->get_all_params();
8✔
698
}
699

700
void SystemImpl::set_param_async(
×
701
    const std::string& name,
702
    ParamValue value,
703
    const SetParamCallback& callback,
704
    const void* cookie,
705
    std::optional<uint8_t> maybe_component_id,
706
    bool extended)
707
{
708
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
709
        ->set_param_async(name, value, callback, cookie);
×
710
}
×
711

712
void SystemImpl::set_param_float_async(
×
713
    const std::string& name,
714
    float value,
715
    const SetParamCallback& callback,
716
    const void* cookie,
717
    std::optional<uint8_t> maybe_component_id,
718
    bool extended)
719
{
720
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
721
        ->set_param_float_async(name, value, callback, cookie);
×
722
}
×
723

724
void SystemImpl::set_param_int_async(
×
725
    const std::string& name,
726
    int32_t value,
727
    const SetParamCallback& callback,
728
    const void* cookie,
729
    std::optional<uint8_t> maybe_component_id,
730
    bool extended)
731
{
732
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
733
        ->set_param_int_async(name, value, callback, cookie);
×
734
}
×
735

736
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
5✔
737
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
738
{
739
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
740
        ->get_param_float(name);
10✔
741
}
742

743
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
744
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
745
{
746
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
747
        ->get_param_int(name);
10✔
748
}
749

750
std::pair<MavlinkParameterClient::Result, std::string>
751
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
752
{
753
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
754
        ->get_param_custom(name);
8✔
755
}
756

757
void SystemImpl::get_param_async(
×
758
    const std::string& name,
759
    ParamValue value,
760
    const GetParamAnyCallback& callback,
761
    const void* cookie,
762
    std::optional<uint8_t> maybe_component_id,
763
    bool extended)
764
{
765
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
766
        ->get_param_async(name, value, callback, cookie);
×
767
}
×
768

769
void SystemImpl::get_param_float_async(
×
770
    const std::string& name,
771
    const GetParamFloatCallback& callback,
772
    const void* cookie,
773
    std::optional<uint8_t> maybe_component_id,
774
    bool extended)
775
{
776
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
777
        ->get_param_float_async(name, callback, cookie);
×
778
}
×
779

780
void SystemImpl::get_param_int_async(
×
781
    const std::string& name,
782
    const GetParamIntCallback& callback,
783
    const void* cookie,
784
    std::optional<uint8_t> maybe_component_id,
785
    bool extended)
786
{
787
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
788
        ->get_param_int_async(name, callback, cookie);
×
789
}
×
790

791
void SystemImpl::get_param_custom_async(
×
792
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
793
{
794
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
795
}
×
796

797
void SystemImpl::cancel_all_param(const void* cookie)
2✔
798
{
799
    UNUSED(cookie);
2✔
800
    // FIXME: this currently crashes on destruction
801
    // param_sender(1, false)->cancel_all_param(cookie);
802
}
2✔
803

804
MavlinkCommandSender::Result
805
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
806
{
807
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
808
        make_command_flight_mode(system_mode, component_id);
×
809

810
    if (result.first != MavlinkCommandSender::Result::Success) {
×
811
        return result.first;
×
812
    }
813

814
    return send_command(result.second);
×
815
}
816

817
void SystemImpl::set_flight_mode_async(
×
818
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
819
{
820
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
821
        make_command_flight_mode(system_mode, component_id);
×
822

823
    if (result.first != MavlinkCommandSender::Result::Success) {
×
824
        if (callback) {
×
825
            callback(result.first, NAN);
×
826
        }
827
        return;
×
828
    }
829

830
    send_command_async(result.second, callback);
×
831
}
832

833
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
834
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
835
{
836
    if (_autopilot == Autopilot::ArduPilot) {
×
837
        return make_command_ardupilot_mode(flight_mode, component_id);
×
838
    } else {
839
        return make_command_px4_mode(flight_mode, component_id);
×
840
    }
841
}
842

843
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
844
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
845
{
846
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
847
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
848
    const uint8_t mode_type =
×
849
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
850

851
    MavlinkCommandSender::CommandLong command{};
×
852

853
    command.command = MAV_CMD_DO_SET_MODE;
×
854
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
855

856
    switch (_vehicle_type) {
×
857
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
858
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER: {
859
            const auto new_mode = flight_mode_to_ardupilot_rover_mode(flight_mode);
×
860
            if (new_mode == ardupilot::RoverMode::Unknown) {
×
861
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
862
                MavlinkCommandSender::CommandLong empty_command{};
×
863
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
864
            } else {
865
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
866
            }
867
            break;
×
868
        }
869
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
870
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
871
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
872
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
873
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
874
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
875
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
876
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
877
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
878
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
879
                MavlinkCommandSender::CommandLong empty_command{};
×
880
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
881
            } else {
882
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
883
            }
884
            break;
×
885
        }
886

887
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
888
        case MAV_TYPE::MAV_TYPE_COAXIAL:
889
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
890
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
891
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
892
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
893
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
894
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
895
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
896
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
897
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
898
                MavlinkCommandSender::CommandLong empty_command{};
×
899
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
900
            } else {
901
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
902
            }
903
            break;
×
904
        }
905

906
        default:
×
907
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
908
                     << _vehicle_type;
×
909
            MavlinkCommandSender::CommandLong empty_command{};
×
910
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
911
    }
912
    command.target_component_id = component_id;
×
913

914
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
915
}
916
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
917
{
918
    switch (flight_mode) {
×
919
        case FlightMode::Mission:
×
920
            return ardupilot::RoverMode::Auto;
×
921
        case FlightMode::Acro:
×
922
            return ardupilot::RoverMode::Acro;
×
923
        case FlightMode::Hold:
×
924
            return ardupilot::RoverMode::Hold;
×
925
        case FlightMode::ReturnToLaunch:
×
926
            return ardupilot::RoverMode::RTL;
×
927
        case FlightMode::Manual:
×
928
            return ardupilot::RoverMode::Manual;
×
929
        case FlightMode::FollowMe:
×
930
            return ardupilot::RoverMode::Follow;
×
931
        case FlightMode::Offboard:
×
932
            return ardupilot::RoverMode::Guided;
×
933
        case FlightMode::Unknown:
×
934
        case FlightMode::Ready:
935
        case FlightMode::Takeoff:
936
        case FlightMode::Land:
937
        case FlightMode::Altctl:
938
        case FlightMode::Posctl:
939
        case FlightMode::Rattitude:
940
        case FlightMode::Stabilized:
941
        default:
942
            return ardupilot::RoverMode::Unknown;
×
943
    }
944
}
945
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
946
{
947
    switch (flight_mode) {
×
948
        case FlightMode::Mission:
×
949
            return ardupilot::CopterMode::Auto;
×
950
        case FlightMode::Acro:
×
951
            return ardupilot::CopterMode::Acro;
×
952
        case FlightMode::Hold:
×
953
            return ardupilot::CopterMode::Loiter;
×
954
        case FlightMode::ReturnToLaunch:
×
955
            return ardupilot::CopterMode::Rtl;
×
956
        case FlightMode::Land:
×
957
            return ardupilot::CopterMode::Land;
×
958
        case FlightMode::Manual:
×
959
            return ardupilot::CopterMode::Stabilize;
×
960
        case FlightMode::FollowMe:
×
961
            return ardupilot::CopterMode::Follow;
×
962
        case FlightMode::Offboard:
×
963
            return ardupilot::CopterMode::Guided;
×
964
        case FlightMode::Altctl:
×
965
            return ardupilot::CopterMode::AltHold;
×
966
        case FlightMode::Posctl:
×
967
            return ardupilot::CopterMode::PosHold;
×
968
        case FlightMode::Stabilized:
×
969
            return ardupilot::CopterMode::Stabilize;
×
970
        case FlightMode::Unknown:
×
971
        case FlightMode::Ready:
972
        case FlightMode::Takeoff:
973
        case FlightMode::Rattitude:
974
        default:
975
            return ardupilot::CopterMode::Unknown;
×
976
    }
977
}
978
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
979
{
980
    switch (flight_mode) {
×
981
        case FlightMode::Mission:
×
982
            return ardupilot::PlaneMode::Auto;
×
983
        case FlightMode::Acro:
×
984
            return ardupilot::PlaneMode::Acro;
×
985
        case FlightMode::Hold:
×
986
            return ardupilot::PlaneMode::Loiter;
×
987
        case FlightMode::ReturnToLaunch:
×
988
            return ardupilot::PlaneMode::Rtl;
×
989
        case FlightMode::Manual:
×
990
            return ardupilot::PlaneMode::Manual;
×
991
        case FlightMode::FBWA:
×
992
            return ardupilot::PlaneMode::Fbwa;
×
993
        case FlightMode::Stabilized:
×
994
            return ardupilot::PlaneMode::Stabilize;
×
995
        case FlightMode::Unknown:
×
996
            return ardupilot::PlaneMode::Unknown;
×
997
        default:
×
998
            return ardupilot::PlaneMode::Unknown;
×
999
    }
1000
}
1001

1002
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
1003
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
1004
{
1005
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1006
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1007

1008
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1009

1010
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1011
    //       but want to be rather safe than sorry.
1012
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1013
    uint8_t custom_sub_mode = 0;
×
1014

1015
    switch (flight_mode) {
×
1016
        case FlightMode::Hold:
×
1017
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
1018
            break;
×
1019
        case FlightMode::ReturnToLaunch:
×
1020
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
1021
            break;
×
1022
        case FlightMode::Takeoff:
×
1023
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
1024
            break;
×
1025
        case FlightMode::Land:
×
1026
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
1027
            break;
×
1028
        case FlightMode::Mission:
×
1029
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
1030
            break;
×
1031
        case FlightMode::FollowMe:
×
1032
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
1033
            break;
×
1034
        case FlightMode::Offboard:
×
1035
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
1036
            break;
×
1037
        case FlightMode::Manual:
×
1038
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
1039
            break;
×
1040
        case FlightMode::Posctl:
×
1041
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
1042
            break;
×
1043
        case FlightMode::Altctl:
×
1044
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
1045
            break;
×
1046
        case FlightMode::Rattitude:
×
1047
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
1048
            break;
×
1049
        case FlightMode::Acro:
×
1050
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1051
            break;
×
1052
        case FlightMode::Stabilized:
×
1053
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1054
            break;
×
1055
        default:
×
1056
            LogErr() << "Unknown Flight mode.";
×
1057
            MavlinkCommandSender::CommandLong empty_command{};
×
1058
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1059
    }
1060

1061
    MavlinkCommandSender::CommandLong command{};
×
1062

1063
    command.command = MAV_CMD_DO_SET_MODE;
×
1064
    command.params.maybe_param1 = static_cast<float>(mode);
×
1065
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1066
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1067
    command.target_component_id = component_id;
×
1068

1069
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1070
}
1071

1072
FlightMode SystemImpl::get_flight_mode() const
6✔
1073
{
1074
    return _flight_mode;
6✔
1075
}
1076

1077
void SystemImpl::receive_float_param(
×
1078
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1079
{
1080
    if (callback) {
×
1081
        if (result == MavlinkParameterClient::Result::Success) {
×
1082
            callback(result, value.get<float>());
×
1083
        } else {
1084
            callback(result, NAN);
×
1085
        }
1086
    }
1087
}
×
1088

1089
void SystemImpl::receive_int_param(
×
1090
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1091
{
1092
    if (callback) {
×
1093
        if (result == MavlinkParameterClient::Result::Success) {
×
1094
            callback(result, value.get<int32_t>());
×
1095
        } else {
1096
            callback(result, 0);
×
1097
        }
1098
    }
1099
}
×
1100

1101
uint8_t SystemImpl::get_autopilot_id() const
50✔
1102
{
1103
    for (auto compid : _components)
60✔
1104
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
50✔
1105
            return compid;
40✔
1106
        }
1107
    // FIXME: Not sure what should be returned if autopilot is not found
1108
    return uint8_t(0);
10✔
1109
}
1110

1111
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1112
{
1113
    std::vector<uint8_t> camera_ids{};
×
1114

1115
    for (auto compid : _components)
×
1116
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1117
            camera_ids.push_back(compid);
×
1118
        }
1119
    return camera_ids;
×
1120
}
1121

1122
uint8_t SystemImpl::get_gimbal_id() const
×
1123
{
1124
    for (auto compid : _components)
×
1125
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1126
            return compid;
×
1127
        }
1128
    return uint8_t(0);
×
1129
}
1130

1131
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
×
1132
{
1133
    if (_target_address.system_id == 0 && _components.empty()) {
×
1134
        return MavlinkCommandSender::Result::NoSystem;
×
1135
    }
1136
    command.target_system_id = get_system_id();
×
1137
    return _command_sender.send_command(command);
×
1138
}
1139

1140
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1141
{
1142
    if (_target_address.system_id == 0 && _components.empty()) {
×
1143
        return MavlinkCommandSender::Result::NoSystem;
×
1144
    }
1145
    command.target_system_id = get_system_id();
×
1146
    return _command_sender.send_command(command);
×
1147
}
1148

1149
void SystemImpl::send_command_async(
14✔
1150
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1151
{
1152
    if (_target_address.system_id == 0 && _components.empty()) {
14✔
1153
        if (callback) {
×
1154
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1155
        }
1156
        return;
×
1157
    }
1158
    command.target_system_id = get_system_id();
14✔
1159

1160
    _command_sender.queue_command_async(command, callback);
14✔
1161
}
1162

1163
void SystemImpl::send_command_async(
×
1164
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1165
{
1166
    if (_target_address.system_id == 0 && _components.empty()) {
×
1167
        if (callback) {
×
1168
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1169
        }
1170
        return;
×
1171
    }
1172
    command.target_system_id = get_system_id();
×
1173

1174
    _command_sender.queue_command_async(command, callback);
×
1175
}
1176

1177
MavlinkCommandSender::Result
1178
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1179
{
1180
    MavlinkCommandSender::CommandLong command =
×
1181
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1182
    return send_command(command);
×
1183
}
1184

1185
void SystemImpl::set_msg_rate_async(
1✔
1186
    uint16_t message_id,
1187
    double rate_hz,
1188
    const CommandResultCallback& callback,
1189
    uint8_t component_id)
1190
{
1191
    MavlinkCommandSender::CommandLong command =
1✔
1192
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1193
    send_command_async(command, callback);
1✔
1194
}
1✔
1195

1196
MavlinkCommandSender::CommandLong
1197
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1198
{
1199
    MavlinkCommandSender::CommandLong command{};
1✔
1200

1201
    // 0 to request default rate, -1 to stop stream
1202

1203
    float interval_us = 0.0f;
1✔
1204

1205
    if (rate_hz > 0) {
1✔
1206
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1207
    } else if (rate_hz < 0) {
×
1208
        interval_us = -1.0f;
×
1209
    }
1210

1211
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1212
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1213
    command.params.maybe_param2 = interval_us;
1✔
1214
    command.target_component_id = component_id;
1✔
1215

1216
    return command;
1✔
1217
}
1218

1219
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
12✔
1220
{
1221
    assert(plugin_impl);
12✔
1222

1223
    plugin_impl->init();
12✔
1224

1225
    {
1226
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
24✔
1227
        _plugin_impls.push_back(plugin_impl);
12✔
1228
    }
1229

1230
    // If we're connected already, let's enable it straightaway.
1231
    if (_connected) {
12✔
1232
        plugin_impl->enable();
12✔
1233
    }
1234
}
12✔
1235

1236
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
12✔
1237
{
1238
    assert(plugin_impl);
12✔
1239

1240
    plugin_impl->disable();
12✔
1241
    plugin_impl->deinit();
12✔
1242

1243
    // Remove first, so it won't get enabled/disabled anymore.
1244
    {
1245
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
24✔
1246
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
12✔
1247
        if (found != _plugin_impls.end()) {
12✔
1248
            _plugin_impls.erase(found);
12✔
1249
        }
1250
    }
1251
}
12✔
1252

1253
void SystemImpl::call_user_callback_located(
14✔
1254
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1255
{
1256
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
14✔
1257
}
14✔
1258

1259
void SystemImpl::param_changed(const std::string& name)
×
1260
{
1261
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1262

1263
    for (auto& callback : _param_changed_callbacks) {
×
1264
        callback.second(name);
×
1265
    }
1266
}
×
1267

1268
void SystemImpl::register_param_changed_handler(
1✔
1269
    const ParamChangedCallback& callback, const void* cookie)
1270
{
1271
    if (!callback) {
1✔
1272
        LogErr() << "No callback for param_changed_handler supplied.";
×
1273
        return;
×
1274
    }
1275

1276
    if (!cookie) {
1✔
1277
        LogErr() << "No callback for param_changed_handler supplied.";
×
1278
        return;
×
1279
    }
1280

1281
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
2✔
1282

1283
    _param_changed_callbacks[cookie] = callback;
1✔
1284
}
1285

1286
void SystemImpl::unregister_param_changed_handler(const void* cookie)
1✔
1287
{
1288
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
1✔
1289

1290
    auto it = _param_changed_callbacks.find(cookie);
1✔
1291
    if (it == _param_changed_callbacks.end()) {
1✔
1292
        LogWarn() << "param_changed_handler for cookie not found";
×
1293
        return;
×
1294
    }
1295
    _param_changed_callbacks.erase(it);
1✔
1296
}
1297

1298
Time& SystemImpl::get_time()
29✔
1299
{
1300
    return _mavsdk_impl.time;
29✔
1301
}
1302

1303
void SystemImpl::subscribe_param_float(
×
1304
    const std::string& name,
1305
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1306
    const void* cookie)
1307
{
1308
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1309
}
×
1310

1311
void SystemImpl::subscribe_param_int(
×
1312
    const std::string& name,
1313
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1314
    const void* cookie)
1315
{
1316
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1317
}
×
1318
void SystemImpl::subscribe_param_custom(
×
1319
    const std::string& name,
1320
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1321
    const void* cookie)
1322
{
1323
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1324
}
×
1325

1326
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
24✔
1327
{
1328
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
48✔
1329

1330
    for (auto& entry : _mavlink_parameter_clients) {
26✔
1331
        if (entry.component_id == component_id && entry.extended == extended) {
18✔
1332
            return entry.parameter_client.get();
16✔
1333
        }
1334
    }
1335

1336
    _mavlink_parameter_clients.push_back(
16✔
1337
        {std::make_unique<MavlinkParameterClient>(
1338
             _mavsdk_impl.default_server_component_impl().sender(),
8✔
1339
             _mavsdk_impl.mavlink_message_handler,
8✔
1340
             _mavsdk_impl.timeout_handler,
8✔
1341
             [this]() { return timeout_s(); },
43✔
1342
             get_system_id(),
16✔
1343
             component_id,
1344
             extended),
1345
         component_id,
1346
         extended});
1347

1348
    return _mavlink_parameter_clients.back().parameter_client.get();
8✔
1349
}
1350

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