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

mavlink / MAVSDK / 15060565035

16 May 2025 04:20AM UTC coverage: 44.332% (+0.06%) from 44.27%
15060565035

push

github

web-flow
Merge pull request #2573 from mavlink/pr-threading

Add incoming and outgoing message queue, fixing threading/locking issues

159 of 185 new or added lines in 7 files covered. (85.95%)

60 existing lines in 8 files now uncovered.

14901 of 33612 relevant lines covered (44.33%)

285.36 hits per line

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

42.55
/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 "callback_list.tpp"
10
#include "unused.h"
11
#include <cassert>
12
#include <cstdlib>
13
#include <functional>
14
#include <future>
15
#include <utility>
16

17
namespace mavsdk {
18

19
template class CallbackList<bool>;
20
template class CallbackList<ComponentType>;
21
template class CallbackList<ComponentType, uint8_t>;
22

23
SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) :
86✔
24
    _mavsdk_impl(mavsdk_impl),
86✔
25
    _command_sender(*this),
86✔
26
    _timesync(*this),
86✔
27
    _ping(*this),
86✔
28
    _mission_transfer_client(
172✔
29
        _mavsdk_impl.default_server_component_impl().sender(),
86✔
30
        _mavlink_message_handler,
86✔
31
        _mavsdk_impl.timeout_handler,
86✔
32
        [this]() { return timeout_s(); },
1✔
33
        [this]() { return autopilot(); }),
1✔
34
    _mavlink_request_message(
86✔
35
        *this, _command_sender, _mavlink_message_handler, _mavsdk_impl.timeout_handler),
86✔
36
    _mavlink_ftp_client(*this),
86✔
37
    _mavlink_component_metadata(*this)
172✔
38
{
39
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
86✔
40
}
86✔
41

42
SystemImpl::~SystemImpl()
86✔
43
{
44
    _should_exit = true;
86✔
45
    _mavlink_message_handler.unregister_all(this);
86✔
46

47
    unregister_timeout_handler(_heartbeat_timeout_cookie);
86✔
48

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

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

62
    _mavlink_message_handler.register_one(
86✔
63
        MAVLINK_MSG_ID_HEARTBEAT,
64
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
162✔
65
        this);
66

67
    _mavlink_message_handler.register_one(
86✔
68
        MAVLINK_MSG_ID_STATUSTEXT,
69
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
70
        this);
71

72
    _mavlink_message_handler.register_one(
86✔
73
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
74
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
33✔
75
        this);
76

77
    add_new_component(comp_id);
86✔
78
}
86✔
79

80
bool SystemImpl::is_connected() const
42✔
81
{
82
    return _connected;
42✔
83
}
84

85
void SystemImpl::register_mavlink_message_handler(
358✔
86
    uint16_t msg_id, const MavlinkMessageHandler::Callback& callback, const void* cookie)
87
{
88
    _mavlink_message_handler.register_one(msg_id, callback, cookie);
358✔
89
}
358✔
90

91
void SystemImpl::register_mavlink_message_handler_with_compid(
×
92
    uint16_t msg_id,
93
    uint8_t component_id,
94
    const MavlinkMessageHandler::Callback& callback,
95
    const void* cookie)
96
{
97
    _mavlink_message_handler.register_one_with_component_id(msg_id, component_id, callback, cookie);
×
98
}
×
99

100
void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
101
{
102
    _mavlink_message_handler.unregister_one(msg_id, cookie);
×
103
}
×
104

105
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
356✔
106
{
107
    _mavlink_message_handler.unregister_all(cookie);
356✔
108
}
356✔
109

110
void SystemImpl::update_component_id_messages_handler(
×
111
    uint16_t msg_id, uint8_t component_id, const void* cookie)
112
{
113
    _mavlink_message_handler.update_component_id(msg_id, component_id, cookie);
×
114
}
×
115

116
TimeoutHandler::Cookie
117
SystemImpl::register_timeout_handler(const std::function<void()>& callback, double duration_s)
1,091✔
118
{
119
    return _mavsdk_impl.timeout_handler.add(callback, duration_s);
1,091✔
120
}
121

122
void SystemImpl::refresh_timeout_handler(TimeoutHandler::Cookie cookie)
78✔
123
{
124
    _mavsdk_impl.timeout_handler.refresh(cookie);
78✔
125
}
78✔
126

127
void SystemImpl::unregister_timeout_handler(TimeoutHandler::Cookie cookie)
1,212✔
128
{
129
    _mavsdk_impl.timeout_handler.remove(cookie);
1,212✔
130
}
1,212✔
131

132
double SystemImpl::timeout_s() const
1,083✔
133
{
134
    return _mavsdk_impl.timeout_s();
1,083✔
135
}
136

137
void SystemImpl::enable_timesync()
×
138
{
139
    _timesync.enable();
×
140
}
×
141

142
System::IsConnectedHandle
143
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
144
{
145
    return _is_connected_callbacks.subscribe(callback);
×
146
}
147

148
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
149
{
150
    _is_connected_callbacks.unsubscribe(handle);
×
151
}
×
152

153
void SystemImpl::process_mavlink_message(mavlink_message_t& message)
2,043✔
154
{
155
    _mavlink_message_handler.process_message(message);
2,043✔
156
}
2,043✔
157

158
CallEveryHandler::Cookie
159
SystemImpl::add_call_every(std::function<void()> callback, float interval_s)
28✔
160
{
161
    return _mavsdk_impl.call_every_handler.add(
56✔
162
        std::move(callback), static_cast<double>(interval_s));
28✔
163
}
164

165
void SystemImpl::change_call_every(float interval_s, CallEveryHandler::Cookie cookie)
×
166
{
167
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
168
}
×
169

170
void SystemImpl::reset_call_every(CallEveryHandler::Cookie cookie)
×
171
{
172
    _mavsdk_impl.call_every_handler.reset(cookie);
×
173
}
×
174

175
void SystemImpl::remove_call_every(CallEveryHandler::Cookie cookie)
28✔
176
{
177
    _mavsdk_impl.call_every_handler.remove(cookie);
28✔
178
}
28✔
179

180
void SystemImpl::register_statustext_handler(
1✔
181
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
182
{
183
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
1✔
184
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
1✔
185
}
1✔
186

187
void SystemImpl::unregister_statustext_handler(void* cookie)
1✔
188
{
189
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
1✔
190
    _statustext_handler_callbacks.erase(std::remove_if(
1✔
191
        _statustext_handler_callbacks.begin(),
192
        _statustext_handler_callbacks.end(),
193
        [&](const auto& entry) { return entry.cookie == cookie; }));
1✔
194
}
1✔
195

196
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
164✔
197
{
198
    mavlink_heartbeat_t heartbeat;
164✔
199
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
164✔
200

201
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
164✔
202
        _autopilot = Autopilot::Px4;
×
203
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
164✔
204
        _autopilot = Autopilot::ArduPilot;
×
205
    }
206

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

222
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
163✔
223
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
74✔
224
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
74✔
225
    }
226
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
164✔
227
        _flight_mode =
×
228
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
229
    }
230

231
    set_connected();
164✔
232
}
163✔
233

234
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
235
{
236
    mavlink_statustext_t statustext;
3✔
237
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
238

239
    const auto maybe_result = _statustext_handler.process(statustext);
3✔
240

241
    if (maybe_result.has_value()) {
3✔
242
        LogDebug() << "MAVLink: "
6✔
243
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
244
                   << maybe_result.value().text;
9✔
245

246
        std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
3✔
247
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
248
            entry.callback(maybe_result.value());
3✔
249
        }
250
    }
3✔
251
}
3✔
252

253
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
33✔
254
{
255
    mavlink_autopilot_version_t autopilot_version;
33✔
256
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
33✔
257

258
    _mission_transfer_client.set_int_messages_supported(
33✔
259
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
33✔
260
}
33✔
261

262
void SystemImpl::heartbeats_timed_out()
×
263
{
264
    LogInfo() << "heartbeats timed out";
×
265
    set_disconnected();
×
266
}
×
267

268
void SystemImpl::system_thread()
86✔
269
{
270
    SteadyTimePoint last_ping_time{};
86✔
271

272
    while (!_should_exit) {
7,510✔
273
        {
274
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
7,418✔
275
            for (auto& entry : _mavlink_parameter_clients) {
8,361✔
276
                entry.parameter_client->do_work();
938✔
277
            }
278
        }
7,422✔
279
        _command_sender.do_work();
7,422✔
280
        _timesync.do_work();
7,425✔
281
        _mission_transfer_client.do_work();
7,425✔
282
        _mavlink_ftp_client.do_work();
7,422✔
283

284
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
7,424✔
285
            if (_connected && _autopilot != Autopilot::ArduPilot) {
88✔
286
                _ping.run_once();
2✔
287
            }
288
            last_ping_time = _mavsdk_impl.time.steady_time();
88✔
289
        }
290

291
        if (_connected) {
7,421✔
292
            // Work fairly fast if we're connected.
293
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
7,337✔
294
        } else {
295
            // Be less aggressive when unconnected.
296
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
86✔
297
        }
298
    }
299
}
86✔
300

301
std::string SystemImpl::component_name(uint8_t component_id)
87✔
302
{
303
    switch (component_id) {
87✔
304
        case MAV_COMP_ID_AUTOPILOT1:
33✔
305
            return "Autopilot";
33✔
306
        case MAV_COMP_ID_CAMERA:
9✔
307
            return "Camera 1";
9✔
308
        case MAV_COMP_ID_CAMERA2:
×
309
            return "Camera 2";
×
310
        case MAV_COMP_ID_CAMERA3:
×
311
            return "Camera 3";
×
312
        case MAV_COMP_ID_CAMERA4:
×
313
            return "Camera 4";
×
314
        case MAV_COMP_ID_CAMERA5:
×
315
            return "Camera 5";
×
316
        case MAV_COMP_ID_CAMERA6:
×
317
            return "Camera 6";
×
318
        case MAV_COMP_ID_GIMBAL:
×
319
            return "Gimbal";
×
320
        case MAV_COMP_ID_MISSIONPLANNER:
43✔
321
            return "Ground station";
43✔
322
        case MAV_COMP_ID_ONBOARD_COMPUTER:
1✔
323
            return "Companion Computer";
1✔
324
        case MAV_COMP_ID_WINCH:
×
325
            return "Winch";
×
326
        default:
1✔
327
            return "Unsupported component";
1✔
328
    }
329
}
330

331
ComponentType SystemImpl::component_type(uint8_t component_id)
174✔
332
{
333
    switch (component_id) {
174✔
334
        case MAV_COMP_ID_AUTOPILOT1:
66✔
335
            return ComponentType::Autopilot;
66✔
336
        case MAV_COMP_ID_MISSIONPLANNER:
86✔
337
            return ComponentType::GroundStation;
86✔
338
        case MAV_COMP_ID_ONBOARD_COMPUTER:
2✔
339
        case MAV_COMP_ID_ONBOARD_COMPUTER2:
340
        case MAV_COMP_ID_ONBOARD_COMPUTER3:
341
        case MAV_COMP_ID_ONBOARD_COMPUTER4:
342
            return ComponentType::CompanionComputer;
2✔
343
        case MAV_COMP_ID_CAMERA:
18✔
344
        case MAV_COMP_ID_CAMERA2:
345
        case MAV_COMP_ID_CAMERA3:
346
        case MAV_COMP_ID_CAMERA4:
347
        case MAV_COMP_ID_CAMERA5:
348
        case MAV_COMP_ID_CAMERA6:
349
            return ComponentType::Camera;
18✔
350
        case MAV_COMP_ID_GIMBAL:
×
351
            return ComponentType::Gimbal;
×
352
        case MAV_COMP_ID_ODID_TXRX_1:
×
353
        case MAV_COMP_ID_ODID_TXRX_2:
354
        case MAV_COMP_ID_ODID_TXRX_3:
355
            return ComponentType::RemoteId;
×
356
        default:
2✔
357
            return ComponentType::Custom;
2✔
358
    }
359
}
360

361
void SystemImpl::add_new_component(uint8_t component_id)
2,044✔
362
{
363
    if (component_id == 0) {
2,044✔
364
        return;
×
365
    }
366

367
    auto res_pair = _components.insert(component_id);
2,044✔
368
    if (res_pair.second) {
2,044✔
369
        std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
87✔
370
        _component_discovered_callbacks.queue(
87✔
371
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
372
        _component_discovered_id_callbacks.queue(
87✔
373
            component_type(component_id), component_id, [this](const auto& func) {
×
374
                call_user_callback(func);
×
375
            });
×
376
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
348✔
377
                   << ") added.";
348✔
378
    }
87✔
379
}
380

381
size_t SystemImpl::total_components() const
×
382
{
383
    return _components.size();
×
384
}
385

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

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

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

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

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

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

428
bool SystemImpl::is_standalone() const
×
429
{
430
    return !has_autopilot();
×
431
}
432

433
bool SystemImpl::has_autopilot() const
152✔
434
{
435
    return get_autopilot_id() != uint8_t(0);
152✔
436
}
437

438
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
439
{
440
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
441
}
442

443
bool SystemImpl::is_camera(uint8_t comp_id)
9✔
444
{
445
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
9✔
446
}
447

448
bool SystemImpl::has_camera(int camera_id) const
9✔
449
{
450
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
9✔
451

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

466
bool SystemImpl::has_gimbal() const
×
467
{
468
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
469
}
470

471
bool SystemImpl::send_message(mavlink_message_t& message)
×
472
{
473
    return _mavsdk_impl.send_message(message);
×
474
}
475

476
bool SystemImpl::queue_message(
760✔
477
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
478
{
479
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
760✔
480
}
481

482
void SystemImpl::send_autopilot_version_request()
33✔
483
{
484
    mavlink_request_message().request(
33✔
485
        MAVLINK_MSG_ID_AUTOPILOT_VERSION, MAV_COMP_ID_AUTOPILOT1, nullptr);
486
}
33✔
487

488
void SystemImpl::set_connected()
162✔
489
{
490
    bool enable_needed = false;
162✔
491
    {
492
        if (!_connected) {
162✔
493
            if (!_components.empty()) {
86✔
494
                LogDebug() << "Discovered " << _components.size() << " component(s)";
86✔
495
            }
496

497
            _connected = true;
86✔
498

499
            // Only send heartbeats if we're not shutting down
500
            if (!_should_exit) {
86✔
501
                // We call this later to avoid deadlocks on creating the server components.
502
                _mavsdk_impl.call_user_callback([this]() {
172✔
503
                    // Send a heartbeat back immediately.
504
                    _mavsdk_impl.start_sending_heartbeats();
505
                });
506
            }
507

508
            _heartbeat_timeout_cookie =
86✔
509
                register_timeout_handler([this] { heartbeats_timed_out(); }, HEARTBEAT_TIMEOUT_S);
86✔
510

511
            enable_needed = true;
86✔
512

513
            // Queue callbacks without holding any locks to avoid deadlocks
514
            _is_connected_callbacks.queue(
86✔
515
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
516

517
        } else if (_connected) {
76✔
518
            refresh_timeout_handler(_heartbeat_timeout_cookie);
77✔
519
        }
520
        // If not yet connected there is nothing to do
521
    }
522

523
    if (enable_needed) {
164✔
524
        // Notify about the new system without holding any locks
525
        _mavsdk_impl.notify_on_discover();
86✔
526

527
        if (has_autopilot()) {
86✔
528
            send_autopilot_version_request();
33✔
529
        }
530

531
        // Enable plugins
532
        std::vector<PluginImplBase*> plugin_impls_to_enable;
86✔
533
        {
534
            std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
86✔
535
            plugin_impls_to_enable = _plugin_impls;
86✔
536
        }
86✔
537

538
        for (auto plugin_impl : plugin_impls_to_enable) {
86✔
UNCOV
539
            plugin_impl->enable();
×
540
        }
541
    }
86✔
542
}
164✔
543

544
void SystemImpl::set_disconnected()
×
545
{
546
    {
547
        // This might not be needed because this is probably called from the triggered
548
        // timeout anyway, but it should also do no harm.
549
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
550
        //_heartbeat_timeout_cookie = nullptr;
551

552
        _connected = false;
×
553
        _is_connected_callbacks.queue(
×
554
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
555
    }
556
    _mavsdk_impl.notify_on_timeout();
×
557

558
    _mavsdk_impl.stop_sending_heartbeats();
×
559

560
    {
561
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
562
        for (auto plugin_impl : _plugin_impls) {
×
563
            plugin_impl->disable();
×
564
        }
565
    }
×
566
}
×
567

568
uint8_t SystemImpl::get_system_id() const
767✔
569
{
570
    return _target_address.system_id;
767✔
571
}
572

573
std::vector<uint8_t> SystemImpl::component_ids() const
×
574
{
575
    return std::vector<uint8_t>{_components.begin(), _components.end()};
×
576
}
577

578
void SystemImpl::set_system_id(uint8_t system_id)
×
579
{
580
    _target_address.system_id = system_id;
×
581
}
×
582

583
uint8_t SystemImpl::get_own_system_id() const
1,401✔
584
{
585
    return _mavsdk_impl.get_own_system_id();
1,401✔
586
}
587

588
uint8_t SystemImpl::get_own_component_id() const
1,383✔
589
{
590
    return _mavsdk_impl.get_own_component_id();
1,383✔
591
}
592

593
MAV_TYPE SystemImpl::get_vehicle_type() const
×
594
{
595
    return _vehicle_type;
×
596
}
597

598
Vehicle SystemImpl::vehicle() const
×
599
{
600
    return to_vehicle_from_mav_type(_vehicle_type);
×
601
}
602

603
uint8_t SystemImpl::get_own_mav_type() const
×
604
{
605
    return _mavsdk_impl.get_mav_type();
×
606
}
607

608
MavlinkParameterClient::Result SystemImpl::set_param(
×
609
    const std::string& name,
610
    ParamValue value,
611
    std::optional<uint8_t> maybe_component_id,
612
    bool extended)
613
{
614
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
615
        ->set_param(name, value);
×
616
}
617

618
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
619
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
620
{
621
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
622
        ->set_param_float(name, value);
4✔
623
}
624

625
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
626
    const std::string& name,
627
    int32_t value,
628
    std::optional<uint8_t> maybe_component_id,
629
    bool extended)
630
{
631
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
632
        ->set_param_int(name, value);
4✔
633
}
634

635
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
636
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
637
{
638
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
639
        ->set_param_custom(name, value);
4✔
640
}
641

642
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
643
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
644
{
645
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
646
        ->get_all_params();
8✔
647
}
648

649
void SystemImpl::set_param_async(
3✔
650
    const std::string& name,
651
    ParamValue value,
652
    const SetParamCallback& callback,
653
    const void* cookie,
654
    std::optional<uint8_t> maybe_component_id,
655
    bool extended)
656
{
657
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
3✔
658
        ->set_param_async(name, value, callback, cookie);
6✔
659
}
3✔
660

661
void SystemImpl::set_param_float_async(
×
662
    const std::string& name,
663
    float value,
664
    const SetParamCallback& callback,
665
    const void* cookie,
666
    std::optional<uint8_t> maybe_component_id,
667
    bool extended)
668
{
669
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
670
        ->set_param_float_async(name, value, callback, cookie);
×
671
}
×
672

673
void SystemImpl::set_param_int_async(
×
674
    const std::string& name,
675
    int32_t value,
676
    const SetParamCallback& callback,
677
    const void* cookie,
678
    std::optional<uint8_t> maybe_component_id,
679
    bool extended)
680
{
681
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
682
        ->set_param_int_async(name, value, callback, cookie);
×
683
}
×
684

685
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
5✔
686
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
687
{
688
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
689
        ->get_param_float(name);
10✔
690
}
691

692
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
693
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
694
{
695
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
696
        ->get_param_int(name);
10✔
697
}
698

699
std::pair<MavlinkParameterClient::Result, std::string>
700
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
701
{
702
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
703
        ->get_param_custom(name);
8✔
704
}
705

706
void SystemImpl::get_param_async(
×
707
    const std::string& name,
708
    ParamValue value,
709
    const GetParamAnyCallback& callback,
710
    const void* cookie,
711
    std::optional<uint8_t> maybe_component_id,
712
    bool extended)
713
{
714
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
715
        ->get_param_async(name, value, callback, cookie);
×
716
}
×
717

718
void SystemImpl::get_param_float_async(
×
719
    const std::string& name,
720
    const GetParamFloatCallback& callback,
721
    const void* cookie,
722
    std::optional<uint8_t> maybe_component_id,
723
    bool extended)
724
{
725
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
726
        ->get_param_float_async(name, callback, cookie);
×
727
}
×
728

729
void SystemImpl::get_param_int_async(
×
730
    const std::string& name,
731
    const GetParamIntCallback& callback,
732
    const void* cookie,
733
    std::optional<uint8_t> maybe_component_id,
734
    bool extended)
735
{
736
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
737
        ->get_param_int_async(name, callback, cookie);
×
738
}
×
739

740
void SystemImpl::get_param_custom_async(
×
741
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
742
{
743
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
744
}
×
745

746
void SystemImpl::cancel_all_param(const void* cookie)
9✔
747
{
748
    UNUSED(cookie);
9✔
749
    // FIXME: this currently crashes on destruction
750
    // param_sender(1, false)->cancel_all_param(cookie);
751
}
9✔
752

753
MavlinkCommandSender::Result
754
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
755
{
756
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
757
        make_command_flight_mode(system_mode, component_id);
×
758

759
    if (result.first != MavlinkCommandSender::Result::Success) {
×
760
        return result.first;
×
761
    }
762

763
    return send_command(result.second);
×
764
}
765

766
void SystemImpl::set_flight_mode_async(
×
767
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
768
{
769
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
770
        make_command_flight_mode(system_mode, component_id);
×
771

772
    if (result.first != MavlinkCommandSender::Result::Success) {
×
773
        if (callback) {
×
774
            callback(result.first, NAN);
×
775
        }
776
        return;
×
777
    }
778

779
    send_command_async(result.second, callback);
×
780
}
781

782
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
783
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
784
{
785
    if (_autopilot == Autopilot::ArduPilot) {
×
786
        return make_command_ardupilot_mode(flight_mode, component_id);
×
787
    } else {
788
        return make_command_px4_mode(flight_mode, component_id);
×
789
    }
790
}
791

792
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
793
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
794
{
795
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
796
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
797
    const uint8_t mode_type =
×
798
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
799

800
    MavlinkCommandSender::CommandLong command{};
×
801

802
    command.command = MAV_CMD_DO_SET_MODE;
×
803
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
804

805
    switch (_vehicle_type) {
×
806
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
807
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER: {
808
            const auto new_mode = flight_mode_to_ardupilot_rover_mode(flight_mode);
×
809
            if (new_mode == ardupilot::RoverMode::Unknown) {
×
810
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
811
                MavlinkCommandSender::CommandLong empty_command{};
×
812
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
813
            } else {
814
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
815
            }
816
            break;
×
817
        }
818
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
819
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
820
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
821
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
822
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
823
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
824
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
825
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
826
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
827
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
828
                MavlinkCommandSender::CommandLong empty_command{};
×
829
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
830
            } else {
831
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
832
            }
833
            break;
×
834
        }
835

836
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
837
        case MAV_TYPE::MAV_TYPE_COAXIAL:
838
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
839
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
840
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
841
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
842
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
843
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
844
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
845
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
846
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
847
                MavlinkCommandSender::CommandLong empty_command{};
×
848
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
849
            } else {
850
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
851
            }
852
            break;
×
853
        }
854

855
        default:
×
856
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
857
                     << _vehicle_type;
×
858
            MavlinkCommandSender::CommandLong empty_command{};
×
859
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
860
    }
861
    command.target_component_id = component_id;
×
862

863
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
864
}
865
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
866
{
867
    switch (flight_mode) {
×
868
        case FlightMode::Mission:
×
869
            return ardupilot::RoverMode::Auto;
×
870
        case FlightMode::Acro:
×
871
            return ardupilot::RoverMode::Acro;
×
872
        case FlightMode::Hold:
×
873
            return ardupilot::RoverMode::Hold;
×
874
        case FlightMode::ReturnToLaunch:
×
875
            return ardupilot::RoverMode::RTL;
×
876
        case FlightMode::Manual:
×
877
            return ardupilot::RoverMode::Manual;
×
878
        case FlightMode::FollowMe:
×
879
            return ardupilot::RoverMode::Follow;
×
880
        case FlightMode::Offboard:
×
881
            return ardupilot::RoverMode::Guided;
×
882
        case FlightMode::Unknown:
×
883
        case FlightMode::Ready:
884
        case FlightMode::Takeoff:
885
        case FlightMode::Land:
886
        case FlightMode::Altctl:
887
        case FlightMode::Posctl:
888
        case FlightMode::Rattitude:
889
        case FlightMode::Stabilized:
890
        default:
891
            return ardupilot::RoverMode::Unknown;
×
892
    }
893
}
894
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
895
{
896
    switch (flight_mode) {
×
897
        case FlightMode::Mission:
×
898
            return ardupilot::CopterMode::Auto;
×
899
        case FlightMode::Acro:
×
900
            return ardupilot::CopterMode::Acro;
×
901
        case FlightMode::Hold:
×
902
            return ardupilot::CopterMode::Loiter;
×
903
        case FlightMode::ReturnToLaunch:
×
904
            return ardupilot::CopterMode::Rtl;
×
905
        case FlightMode::Land:
×
906
            return ardupilot::CopterMode::Land;
×
907
        case FlightMode::Manual:
×
908
            return ardupilot::CopterMode::Stabilize;
×
909
        case FlightMode::FollowMe:
×
910
            return ardupilot::CopterMode::Follow;
×
911
        case FlightMode::Offboard:
×
912
            return ardupilot::CopterMode::Guided;
×
913
        case FlightMode::Altctl:
×
914
            return ardupilot::CopterMode::AltHold;
×
915
        case FlightMode::Posctl:
×
916
            return ardupilot::CopterMode::PosHold;
×
917
        case FlightMode::Stabilized:
×
918
            return ardupilot::CopterMode::Stabilize;
×
919
        case FlightMode::Unknown:
×
920
        case FlightMode::Ready:
921
        case FlightMode::Takeoff:
922
        case FlightMode::Rattitude:
923
        default:
924
            return ardupilot::CopterMode::Unknown;
×
925
    }
926
}
927
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
928
{
929
    switch (flight_mode) {
×
930
        case FlightMode::Mission:
×
931
            return ardupilot::PlaneMode::Auto;
×
932
        case FlightMode::Acro:
×
933
            return ardupilot::PlaneMode::Acro;
×
934
        case FlightMode::Hold:
×
935
            return ardupilot::PlaneMode::Loiter;
×
936
        case FlightMode::ReturnToLaunch:
×
937
            return ardupilot::PlaneMode::Rtl;
×
938
        case FlightMode::Manual:
×
939
            return ardupilot::PlaneMode::Manual;
×
940
        case FlightMode::FBWA:
×
941
            return ardupilot::PlaneMode::Fbwa;
×
942
        case FlightMode::Stabilized:
×
943
            return ardupilot::PlaneMode::Stabilize;
×
944
        case FlightMode::Offboard:
×
945
            return ardupilot::PlaneMode::Guided;
×
946
        case FlightMode::Unknown:
×
947
            return ardupilot::PlaneMode::Unknown;
×
948
        default:
×
949
            return ardupilot::PlaneMode::Unknown;
×
950
    }
951
}
952

953
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
954
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
955
{
956
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
957
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
958

959
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
960

961
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
962
    //       but want to be rather safe than sorry.
963
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
964
    uint8_t custom_sub_mode = 0;
×
965

966
    switch (flight_mode) {
×
967
        case FlightMode::Hold:
×
968
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
969
            break;
×
970
        case FlightMode::ReturnToLaunch:
×
971
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
972
            break;
×
973
        case FlightMode::Takeoff:
×
974
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
975
            break;
×
976
        case FlightMode::Land:
×
977
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
978
            break;
×
979
        case FlightMode::Mission:
×
980
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
981
            break;
×
982
        case FlightMode::FollowMe:
×
983
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
984
            break;
×
985
        case FlightMode::Offboard:
×
986
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
987
            break;
×
988
        case FlightMode::Manual:
×
989
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
990
            break;
×
991
        case FlightMode::Posctl:
×
992
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
993
            break;
×
994
        case FlightMode::Altctl:
×
995
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
996
            break;
×
997
        case FlightMode::Rattitude:
×
998
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
999
            break;
×
1000
        case FlightMode::Acro:
×
1001
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1002
            break;
×
1003
        case FlightMode::Stabilized:
×
1004
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1005
            break;
×
1006
        default:
×
1007
            LogErr() << "Unknown Flight mode.";
×
1008
            MavlinkCommandSender::CommandLong empty_command{};
×
1009
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1010
    }
1011

1012
    MavlinkCommandSender::CommandLong command{};
×
1013

1014
    command.command = MAV_CMD_DO_SET_MODE;
×
1015
    command.params.maybe_param1 = static_cast<float>(mode);
×
1016
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1017
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1018
    command.target_component_id = component_id;
×
1019

1020
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1021
}
1022

1023
FlightMode SystemImpl::get_flight_mode() const
6✔
1024
{
1025
    return _flight_mode;
6✔
1026
}
1027

1028
void SystemImpl::receive_float_param(
×
1029
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1030
{
1031
    if (callback) {
×
1032
        if (result == MavlinkParameterClient::Result::Success) {
×
1033
            callback(result, value.get<float>());
×
1034
        } else {
1035
            callback(result, NAN);
×
1036
        }
1037
    }
1038
}
×
1039

1040
void SystemImpl::receive_int_param(
×
1041
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1042
{
1043
    if (callback) {
×
1044
        if (result == MavlinkParameterClient::Result::Success) {
×
1045
            callback(result, value.get<int32_t>());
×
1046
        } else {
1047
            callback(result, 0);
×
1048
        }
1049
    }
1050
}
×
1051

1052
uint8_t SystemImpl::get_autopilot_id() const
197✔
1053
{
1054
    for (auto compid : _components)
257✔
1055
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
200✔
1056
            return compid;
140✔
1057
        }
1058
    // FIXME: Not sure what should be returned if autopilot is not found
1059
    return uint8_t(0);
57✔
1060
}
1061

1062
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1063
{
1064
    std::vector<uint8_t> camera_ids{};
×
1065

1066
    for (auto compid : _components)
×
1067
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1068
            camera_ids.push_back(compid);
×
1069
        }
1070
    return camera_ids;
×
1071
}
1072

1073
uint8_t SystemImpl::get_gimbal_id() const
×
1074
{
1075
    for (auto compid : _components)
×
1076
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1077
            return compid;
×
1078
        }
1079
    return uint8_t(0);
×
1080
}
1081

1082
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
5✔
1083
{
1084
    if (_target_address.system_id == 0 && _components.empty()) {
5✔
1085
        return MavlinkCommandSender::Result::NoSystem;
×
1086
    }
1087
    command.target_system_id = get_system_id();
5✔
1088
    return _command_sender.send_command(command);
5✔
1089
}
1090

1091
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1092
{
1093
    if (_target_address.system_id == 0 && _components.empty()) {
×
1094
        return MavlinkCommandSender::Result::NoSystem;
×
1095
    }
1096
    command.target_system_id = get_system_id();
×
1097
    return _command_sender.send_command(command);
×
1098
}
1099

1100
void SystemImpl::send_command_async(
7✔
1101
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1102
{
1103
    if (_target_address.system_id == 0 && _components.empty()) {
7✔
1104
        if (callback) {
×
1105
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1106
        }
1107
        return;
×
1108
    }
1109
    command.target_system_id = get_system_id();
7✔
1110

1111
    _command_sender.queue_command_async(command, callback);
7✔
1112
}
1113

1114
void SystemImpl::send_command_async(
×
1115
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1116
{
1117
    if (_target_address.system_id == 0 && _components.empty()) {
×
1118
        if (callback) {
×
1119
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1120
        }
1121
        return;
×
1122
    }
1123
    command.target_system_id = get_system_id();
×
1124

1125
    _command_sender.queue_command_async(command, callback);
×
1126
}
1127

1128
MavlinkCommandSender::Result
1129
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1130
{
1131
    MavlinkCommandSender::CommandLong command =
×
1132
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1133
    return send_command(command);
×
1134
}
1135

1136
void SystemImpl::set_msg_rate_async(
1✔
1137
    uint16_t message_id,
1138
    double rate_hz,
1139
    const CommandResultCallback& callback,
1140
    uint8_t component_id)
1141
{
1142
    MavlinkCommandSender::CommandLong command =
1✔
1143
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1144
    send_command_async(command, callback);
1✔
1145
}
1✔
1146

1147
MavlinkCommandSender::CommandLong
1148
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1149
{
1150
    MavlinkCommandSender::CommandLong command{};
1✔
1151

1152
    // 0 to request default rate, -1 to stop stream
1153

1154
    float interval_us = 0.0f;
1✔
1155

1156
    if (rate_hz > 0) {
1✔
1157
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1158
    } else if (rate_hz < 0) {
×
1159
        interval_us = -1.0f;
×
1160
    }
1161

1162
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1163
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1164
    command.params.maybe_param2 = interval_us;
1✔
1165
    command.target_component_id = component_id;
1✔
1166

1167
    return command;
1✔
1168
}
1169

1170
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
45✔
1171
{
1172
    assert(plugin_impl);
45✔
1173

1174
    plugin_impl->init();
45✔
1175

1176
    {
1177
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
45✔
1178
        _plugin_impls.push_back(plugin_impl);
45✔
1179
    }
45✔
1180

1181
    // If we're connected already, let's enable it straightaway.
1182
    if (_connected) {
45✔
1183
        plugin_impl->enable();
45✔
1184
    }
1185
}
45✔
1186

1187
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
45✔
1188
{
1189
    assert(plugin_impl);
45✔
1190

1191
    plugin_impl->disable();
45✔
1192
    plugin_impl->deinit();
45✔
1193

1194
    // Remove first, so it won't get enabled/disabled anymore.
1195
    {
1196
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
45✔
1197
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
45✔
1198
        if (found != _plugin_impls.end()) {
45✔
1199
            _plugin_impls.erase(found);
45✔
1200
        }
1201
    }
45✔
1202
}
45✔
1203

1204
void SystemImpl::call_user_callback_located(
906✔
1205
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1206
{
1207
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
906✔
1208
}
906✔
1209

1210
void SystemImpl::param_changed(const std::string& name)
×
1211
{
1212
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1213

1214
    for (auto& callback : _param_changed_callbacks) {
×
1215
        callback.second(name);
×
1216
    }
1217
}
×
1218

1219
void SystemImpl::register_param_changed_handler(
×
1220
    const ParamChangedCallback& callback, const void* cookie)
1221
{
1222
    if (!callback) {
×
1223
        LogErr() << "No callback for param_changed_handler supplied.";
×
1224
        return;
×
1225
    }
1226

1227
    if (!cookie) {
×
1228
        LogErr() << "No callback for param_changed_handler supplied.";
×
1229
        return;
×
1230
    }
1231

1232
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1233

1234
    _param_changed_callbacks[cookie] = callback;
×
1235
}
×
1236

1237
void SystemImpl::unregister_param_changed_handler(const void* cookie)
×
1238
{
1239
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1240

1241
    auto it = _param_changed_callbacks.find(cookie);
×
1242
    if (it == _param_changed_callbacks.end()) {
×
1243
        LogWarn() << "param_changed_handler for cookie not found";
×
1244
        return;
×
1245
    }
1246
    _param_changed_callbacks.erase(it);
×
1247
}
×
1248

1249
Time& SystemImpl::get_time()
414✔
1250
{
1251
    return _mavsdk_impl.time;
414✔
1252
}
1253

1254
void SystemImpl::subscribe_param_float(
×
1255
    const std::string& name,
1256
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1257
    const void* cookie)
1258
{
1259
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1260
}
×
1261

1262
void SystemImpl::subscribe_param_int(
×
1263
    const std::string& name,
1264
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1265
    const void* cookie)
1266
{
1267
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1268
}
×
1269
void SystemImpl::subscribe_param_custom(
×
1270
    const std::string& name,
1271
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1272
    const void* cookie)
1273
{
1274
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1275
}
×
1276

1277
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
86✔
1278
{
1279
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
86✔
1280

1281
    for (auto& entry : _mavlink_parameter_clients) {
88✔
1282
        if (entry.component_id == component_id && entry.extended == extended) {
78✔
1283
            return entry.parameter_client.get();
76✔
1284
        }
1285
    }
1286

1287
    _mavlink_parameter_clients.push_back(
30✔
1288
        {std::make_unique<MavlinkParameterClient>(
1289
             _mavsdk_impl.default_server_component_impl().sender(),
10✔
1290
             _mavlink_message_handler,
10✔
1291
             _mavsdk_impl.timeout_handler,
10✔
1292
             [this]() { return timeout_s(); },
80✔
1293
             [this]() { return autopilot(); },
32✔
1294
             get_system_id(),
20✔
1295
             component_id,
1296
             extended),
1297
         component_id,
1298
         extended});
1299

1300
    return _mavlink_parameter_clients.back().parameter_client.get();
10✔
1301
}
86✔
1302

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