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

mavlink / MAVSDK / 19833112496

01 Dec 2025 06:23PM UTC coverage: 48.262% (+0.05%) from 48.21%
19833112496

push

github

web-flow
Merge pull request #2721 from mavlink/pr-destruction-segfault

Fix segfaults on events destruction

19 of 35 new or added lines in 19 files covered. (54.29%)

6 existing lines in 5 files now uncovered.

17657 of 36586 relevant lines covered (48.26%)

467.21 hits per line

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

45.71
/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 <mav/MessageSet.h>
6
#include "server_component_impl.h"
7
#include "plugin_impl_base.h"
8
#include "px4_custom_mode.h"
9
#include "ardupilot_custom_mode.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<ComponentType>;
22
template class CallbackList<ComponentType, uint8_t>;
23

24
SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) :
138✔
25
    _mavsdk_impl(mavsdk_impl),
138✔
26
    _command_sender(*this),
138✔
27
    _timesync(*this),
138✔
28
    _ping(*this),
138✔
29
    _mission_transfer_client(
276✔
30
        _mavsdk_impl.default_server_component_impl().sender(),
138✔
31
        _mavlink_message_handler,
138✔
32
        _mavsdk_impl.timeout_handler,
138✔
33
        [this]() { return timeout_s(); },
1✔
34
        [this]() { return autopilot(); }),
1✔
35
    _mavlink_request_message(
138✔
36
        *this, _command_sender, _mavlink_message_handler, _mavsdk_impl.timeout_handler),
138✔
37
    _mavlink_ftp_client(*this),
138✔
38
    _mavlink_component_metadata(*this)
276✔
39
{
40
    if (const char* env_p = std::getenv("MAVSDK_MESSAGE_DEBUGGING")) {
138✔
41
        if (std::string(env_p) == "1") {
×
42
            _message_debugging = true;
×
43
        }
44
    }
45

46
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
138✔
47
}
138✔
48

49
SystemImpl::~SystemImpl()
138✔
50
{
51
    _should_exit = true;
138✔
52
    // Use blocking version to ensure any in-flight callbacks complete before destruction.
53
    _mavlink_message_handler.unregister_all_blocking(this);
138✔
54
    // Clear all libmav message callbacks
55
    _libmav_message_callbacks.clear();
138✔
56

57
    unregister_timeout_handler(_heartbeat_timeout_cookie);
138✔
58

59
    if (_system_thread != nullptr) {
138✔
60
        _system_thread->join();
138✔
61
        delete _system_thread;
138✔
62
        _system_thread = nullptr;
138✔
63
    }
64
}
138✔
65

66
void SystemImpl::init(uint8_t system_id, uint8_t comp_id)
138✔
67
{
68
    _target_address.system_id = system_id;
138✔
69
    // We use this as a default.
70
    _target_address.component_id = MAV_COMP_ID_AUTOPILOT1;
138✔
71

72
    _mavlink_message_handler.register_one(
138✔
73
        MAVLINK_MSG_ID_HEARTBEAT,
74
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
379✔
75
        this);
76

77
    _mavlink_message_handler.register_one(
138✔
78
        MAVLINK_MSG_ID_STATUSTEXT,
79
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
80
        this);
81

82
    _mavlink_message_handler.register_one(
138✔
83
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
84
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
67✔
85
        this);
86

87
    add_new_component(comp_id);
138✔
88
}
138✔
89

90
bool SystemImpl::is_connected() const
67✔
91
{
92
    return _connected;
67✔
93
}
94

95
void SystemImpl::register_mavlink_message_handler(
634✔
96
    uint16_t msg_id, const MavlinkMessageHandler::Callback& callback, const void* cookie)
97
{
98
    _mavlink_message_handler.register_one(msg_id, callback, cookie);
634✔
99
}
634✔
100

101
void SystemImpl::register_mavlink_message_handler_with_compid(
×
102
    uint16_t msg_id,
103
    uint8_t component_id,
104
    const MavlinkMessageHandler::Callback& callback,
105
    const void* cookie)
106
{
107
    _mavlink_message_handler.register_one_with_component_id(msg_id, component_id, callback, cookie);
×
108
}
×
109

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

115
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
552✔
116
{
117
    _mavlink_message_handler.unregister_all(cookie);
552✔
118
}
552✔
119

120
void SystemImpl::unregister_all_mavlink_message_handlers_blocking(const void* cookie)
17✔
121
{
122
    _mavlink_message_handler.unregister_all_blocking(cookie);
17✔
123
}
17✔
124

UNCOV
125
void SystemImpl::update_component_id_messages_handler(
×
126
    uint16_t msg_id, uint8_t component_id, const void* cookie)
127
{
128
    _mavlink_message_handler.update_component_id(msg_id, component_id, cookie);
×
129
}
×
130

131
void SystemImpl::process_libmav_message(const Mavsdk::MavlinkMessage& message)
2,498✔
132
{
133
    if (_message_debugging) {
2,498✔
134
        LogDebug() << "SystemImpl::process_libmav_message: " << message.message_name;
×
135
    }
136

137
    // CallbackList handles thread safety - just call all callbacks and let them filter internally
138
    _libmav_message_callbacks.queue(
2,498✔
139
        message, [this](const std::function<void()>& callback_wrapper) { callback_wrapper(); });
109✔
140
}
2,491✔
141

142
Handle<Mavsdk::MavlinkMessage> SystemImpl::register_libmav_message_handler(
30✔
143
    const std::string& message_name, const LibmavMessageCallback& callback)
144
{
145
    // Create a filtering callback that only calls the user callback for matching messages
146
    auto filtering_callback =
147
        [this, message_name, callback](const Mavsdk::MavlinkMessage& message) {
217✔
148
            if (_message_debugging) {
109✔
149
                LogDebug() << "Checking handler for message: '" << message_name << "' against '"
×
150
                           << message.message_name << "'";
×
151
            }
152

153
            // Check if message name matches (empty string means match all messages)
154
            if (!message_name.empty() && message_name != message.message_name) {
109✔
155
                if (_message_debugging) {
×
156
                    LogDebug() << "Handler message name mismatch, skipping";
×
157
                }
158
                return;
×
159
            }
160

161
            // Call the user callback
162
            if (_message_debugging) {
108✔
163
                LogDebug() << "Calling libmav handler for: " << message.message_name;
×
164
            }
165
            callback(message);
108✔
166
        };
30✔
167

168
    auto handle = _libmav_message_callbacks.subscribe(filtering_callback);
30✔
169

170
    if (_message_debugging) {
30✔
171
        LogDebug() << "Registering libmav handler for message: '" << message_name << "'";
×
172
    }
173

174
    return handle;
60✔
175
}
30✔
176

177
Handle<Mavsdk::MavlinkMessage> SystemImpl::register_libmav_message_handler_with_compid(
×
178
    const std::string& message_name, uint8_t cmp_id, const LibmavMessageCallback& callback)
179
{
180
    // Create a filtering callback that only calls the user callback for matching messages
181
    auto filtering_callback =
182
        [this, message_name, cmp_id, callback](const Mavsdk::MavlinkMessage& message) {
×
183
            if (_message_debugging) {
×
184
                LogDebug() << "Checking handler for message: '" << message_name << "' against '"
×
185
                           << message.message_name
×
186
                           << "' with component ID: " << static_cast<int>(cmp_id);
×
187
            }
188

189
            // Check if message name matches (empty string means match all messages)
190
            if (!message_name.empty() && message_name != message.message_name) {
×
191
                if (_message_debugging) {
×
192
                    LogDebug() << "Handler message name mismatch, skipping";
×
193
                }
194
                return;
×
195
            }
196

197
            // Check if component ID matches
198
            if (cmp_id != message.component_id) {
×
199
                if (_message_debugging) {
×
200
                    LogDebug() << "Handler component ID mismatch, skipping";
×
201
                }
202
                return;
×
203
            }
204

205
            // Call the user callback
206
            if (_message_debugging) {
×
207
                LogDebug() << "Calling libmav handler for: " << message.message_name;
×
208
            }
209
            callback(message);
×
210
        };
×
211

212
    auto handle = _libmav_message_callbacks.subscribe(filtering_callback);
×
213

214
    if (_message_debugging) {
×
215
        LogDebug() << "Registering libmav handler for message: '" << message_name
×
216
                   << "' with component ID: " << static_cast<int>(cmp_id);
×
217
    }
218

219
    return handle;
×
220
}
×
221

222
void SystemImpl::unregister_libmav_message_handler(Handle<Mavsdk::MavlinkMessage> handle)
30✔
223
{
224
    _libmav_message_callbacks.unsubscribe(handle);
30✔
225

226
    if (_message_debugging) {
30✔
227
        LogDebug() << "Unregistered libmav handler";
×
228
    }
229
}
30✔
230

231
TimeoutHandler::Cookie
232
SystemImpl::register_timeout_handler(const std::function<void()>& callback, double duration_s)
1,204✔
233
{
234
    return _mavsdk_impl.timeout_handler.add(callback, duration_s);
1,204✔
235
}
236

237
void SystemImpl::refresh_timeout_handler(TimeoutHandler::Cookie cookie)
237✔
238
{
239
    _mavsdk_impl.timeout_handler.refresh(cookie);
237✔
240
}
235✔
241

242
void SystemImpl::unregister_timeout_handler(TimeoutHandler::Cookie cookie)
1,397✔
243
{
244
    _mavsdk_impl.timeout_handler.remove(cookie);
1,397✔
245
}
1,397✔
246

247
double SystemImpl::timeout_s() const
1,130✔
248
{
249
    return _mavsdk_impl.timeout_s();
1,130✔
250
}
251

252
void SystemImpl::enable_timesync()
×
253
{
254
    _timesync.enable();
×
255
}
×
256

257
System::IsConnectedHandle
258
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
259
{
260
    return _is_connected_callbacks.subscribe(callback);
×
261
}
262

263
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
264
{
265
    _is_connected_callbacks.unsubscribe(handle);
×
266
}
×
267

268
void SystemImpl::process_mavlink_message(mavlink_message_t& message)
2,465✔
269
{
270
    _mavlink_message_handler.process_message(message);
2,465✔
271
}
2,471✔
272

273
CallEveryHandler::Cookie
274
SystemImpl::add_call_every(std::function<void()> callback, float interval_s)
33✔
275
{
276
    return _mavsdk_impl.call_every_handler.add(
66✔
277
        std::move(callback), static_cast<double>(interval_s));
66✔
278
}
279

280
void SystemImpl::change_call_every(float interval_s, CallEveryHandler::Cookie cookie)
×
281
{
282
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
283
}
×
284

285
void SystemImpl::reset_call_every(CallEveryHandler::Cookie cookie)
×
286
{
287
    _mavsdk_impl.call_every_handler.reset(cookie);
×
288
}
×
289

290
void SystemImpl::remove_call_every(CallEveryHandler::Cookie cookie)
33✔
291
{
292
    _mavsdk_impl.call_every_handler.remove(cookie);
33✔
293
}
33✔
294

295
void SystemImpl::register_statustext_handler(
6✔
296
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
297
{
298
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
6✔
299
}
6✔
300

301
void SystemImpl::unregister_statustext_handler(void* cookie)
6✔
302
{
303
    _statustext_handler_callbacks.erase(std::remove_if(
6✔
304
        _statustext_handler_callbacks.begin(),
305
        _statustext_handler_callbacks.end(),
306
        [&](const auto& entry) { return entry.cookie == cookie; }));
6✔
307
}
6✔
308

309
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
380✔
310
{
311
    mavlink_heartbeat_t heartbeat;
312
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
380✔
313

314
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
378✔
315
        _autopilot = Autopilot::Px4;
×
316
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
378✔
317
        _autopilot = Autopilot::ArduPilot;
5✔
318
    }
319

320
    // Only set the vehicle type if the heartbeat is from an autopilot component
321
    // This check only works if the MAV_TYPE::MAV_TYPE_ENUM_END is actually the
322
    // last enumerator.
323
    if (MAV_TYPE::MAV_TYPE_ENUM_END < heartbeat.type) {
373✔
324
        LogErr() << "type received in HEARTBEAT was not recognized";
×
325
    } else {
326
        const auto new_vehicle_type = static_cast<MAV_TYPE>(heartbeat.type);
373✔
327
        if (heartbeat.autopilot != MAV_AUTOPILOT_INVALID && _vehicle_type != new_vehicle_type &&
373✔
328
            new_vehicle_type != MAV_TYPE_GENERIC) {
329
            LogWarn() << "Vehicle type changed (new type: " << static_cast<unsigned>(heartbeat.type)
3✔
330
                      << ", old type: " << static_cast<unsigned>(_vehicle_type) << ")";
3✔
331
            _vehicle_type = new_vehicle_type;
3✔
332
        }
333
    }
334

335
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
373✔
336
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
181✔
337
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
181✔
338
    }
339
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
377✔
340
        _flight_mode =
5✔
341
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
342
    }
343

344
    set_connected();
377✔
345
}
381✔
346

347
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
348
{
349
    mavlink_statustext_t statustext;
350
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
351

352
    const auto maybe_result = _statustext_handler.process(statustext);
3✔
353

354
    if (maybe_result.has_value()) {
3✔
355
        LogDebug() << "MAVLink: "
3✔
356
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
357
                   << maybe_result.value().text;
3✔
358

359
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
360
            entry.callback(maybe_result.value());
3✔
361
        }
362
    }
363
}
3✔
364

365
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
67✔
366
{
367
    mavlink_autopilot_version_t autopilot_version;
368
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
67✔
369

370
    _mission_transfer_client.set_int_messages_supported(
67✔
371
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
67✔
372
}
67✔
373

374
void SystemImpl::heartbeats_timed_out()
5✔
375
{
376
    LogInfo() << "heartbeats timed out";
5✔
377
    set_disconnected();
5✔
378
}
5✔
379

380
void SystemImpl::system_thread()
138✔
381
{
382
    SteadyTimePoint last_ping_time{};
138✔
383

384
    while (!_should_exit) {
18,239✔
385
        {
386
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
17,858✔
387
            for (auto& entry : _mavlink_parameter_clients) {
18,304✔
388
                entry.parameter_client->do_work();
938✔
389
            }
390
        }
17,156✔
391
        _command_sender.do_work();
17,812✔
392
        _timesync.do_work();
17,625✔
393
        _mission_transfer_client.do_work();
17,777✔
394
        _mavlink_ftp_client.do_work();
17,597✔
395

396
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
17,566✔
397
            if (_connected && _autopilot != Autopilot::ArduPilot) {
147✔
398
                _ping.run_once();
20✔
399
            }
400
            last_ping_time = _mavsdk_impl.time.steady_time();
148✔
401
        }
402

403
        if (_connected) {
16,830✔
404
            // Work fairly fast if we're connected.
405
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
16,952✔
406
        } else {
407
            // Be less aggressive when unconnected.
408
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
160✔
409
        }
410
    }
411
}
28✔
412

413
std::string SystemImpl::component_name(uint8_t component_id)
141✔
414
{
415
    switch (component_id) {
141✔
416
        case MAV_COMP_ID_AUTOPILOT1:
58✔
417
            return "Autopilot";
58✔
418
        case MAV_COMP_ID_CAMERA:
9✔
419
            return "Camera 1";
9✔
420
        case MAV_COMP_ID_CAMERA2:
×
421
            return "Camera 2";
×
422
        case MAV_COMP_ID_CAMERA3:
×
423
            return "Camera 3";
×
424
        case MAV_COMP_ID_CAMERA4:
×
425
            return "Camera 4";
×
426
        case MAV_COMP_ID_CAMERA5:
×
427
            return "Camera 5";
×
428
        case MAV_COMP_ID_CAMERA6:
×
429
            return "Camera 6";
×
430
        case MAV_COMP_ID_GIMBAL:
×
431
            return "Gimbal";
×
432
        case MAV_COMP_ID_MISSIONPLANNER:
68✔
433
            return "Ground station";
68✔
434
        case MAV_COMP_ID_ONBOARD_COMPUTER:
1✔
435
            return "Companion Computer";
1✔
436
        case MAV_COMP_ID_WINCH:
×
437
            return "Winch";
×
438
        default:
5✔
439
            return "Unsupported component";
5✔
440
    }
441
}
442

443
ComponentType SystemImpl::component_type(uint8_t component_id)
282✔
444
{
445
    switch (component_id) {
282✔
446
        case MAV_COMP_ID_AUTOPILOT1:
116✔
447
            return ComponentType::Autopilot;
116✔
448
        case MAV_COMP_ID_MISSIONPLANNER:
136✔
449
            return ComponentType::GroundStation;
136✔
450
        case MAV_COMP_ID_ONBOARD_COMPUTER:
2✔
451
        case MAV_COMP_ID_ONBOARD_COMPUTER2:
452
        case MAV_COMP_ID_ONBOARD_COMPUTER3:
453
        case MAV_COMP_ID_ONBOARD_COMPUTER4:
454
            return ComponentType::CompanionComputer;
2✔
455
        case MAV_COMP_ID_CAMERA:
18✔
456
        case MAV_COMP_ID_CAMERA2:
457
        case MAV_COMP_ID_CAMERA3:
458
        case MAV_COMP_ID_CAMERA4:
459
        case MAV_COMP_ID_CAMERA5:
460
        case MAV_COMP_ID_CAMERA6:
461
            return ComponentType::Camera;
18✔
462
        case MAV_COMP_ID_GIMBAL:
×
463
            return ComponentType::Gimbal;
×
464
        case MAV_COMP_ID_ODID_TXRX_1:
×
465
        case MAV_COMP_ID_ODID_TXRX_2:
466
        case MAV_COMP_ID_ODID_TXRX_3:
467
            return ComponentType::RemoteId;
×
468
        default:
10✔
469
            return ComponentType::Custom;
10✔
470
    }
471
}
472

473
void SystemImpl::add_new_component(uint8_t component_id)
4,963✔
474
{
475
    if (component_id == 0) {
4,963✔
476
        return;
×
477
    }
478

479
    bool is_new_component = false;
4,963✔
480
    {
481
        std::lock_guard<std::mutex> lock(_components_mutex);
4,963✔
482
        auto res_pair = _components.insert(component_id);
4,969✔
483
        is_new_component = res_pair.second;
4,964✔
484
    }
4,964✔
485

486
    if (is_new_component) {
4,968✔
487
        _component_discovered_callbacks.queue(
141✔
488
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
489
        _component_discovered_id_callbacks.queue(
141✔
490
            component_type(component_id), component_id, [this](const auto& func) {
×
491
                call_user_callback(func);
×
492
            });
×
493
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
282✔
494
                   << ") added.";
141✔
495
    }
496
}
497

498
size_t SystemImpl::total_components() const
×
499
{
500
    std::lock_guard<std::mutex> lock(_components_mutex);
×
501
    return _components.size();
×
502
}
×
503

504
System::ComponentDiscoveredHandle
505
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
506
{
507
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
508

509
    if (total_components() > 0) {
×
510
        std::lock_guard<std::mutex> components_lock(_components_mutex);
×
511
        for (const auto& elem : _components) {
×
512
            _component_discovered_callbacks.queue(
×
513
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
514
        }
515
    }
×
516
    return handle;
×
517
}
518

519
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
520
{
521
    _component_discovered_callbacks.unsubscribe(handle);
×
522
}
×
523

524
System::ComponentDiscoveredIdHandle
525
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
526
{
527
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
528

529
    if (total_components() > 0) {
×
530
        std::lock_guard<std::mutex> components_lock(_components_mutex);
×
531
        for (const auto& elem : _components) {
×
532
            _component_discovered_id_callbacks.queue(
×
533
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
534
        }
535
    }
×
536
    return handle;
×
537
}
538

539
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
540
{
541
    _component_discovered_id_callbacks.unsubscribe(handle);
×
542
}
×
543

544
bool SystemImpl::is_standalone() const
×
545
{
546
    return !has_autopilot();
×
547
}
548

549
bool SystemImpl::has_autopilot() const
251✔
550
{
551
    return get_autopilot_id() != uint8_t(0);
251✔
552
}
553

554
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
555
{
556
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
557
}
558

559
bool SystemImpl::is_camera(uint8_t comp_id)
9✔
560
{
561
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
9✔
562
}
563

564
bool SystemImpl::has_camera(int camera_id) const
9✔
565
{
566
    std::lock_guard<std::mutex> lock(_components_mutex);
9✔
567
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
9✔
568

569
    if (camera_comp_id == -1) { // Check whether the system has any camera.
9✔
570
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
9✔
571
            return true;
9✔
572
        }
573
    } else { // Look for the camera whose id is `camera_id`.
574
        for (auto compid : _components) {
×
575
            if (compid == camera_comp_id) {
×
576
                return true;
×
577
            }
578
        }
579
    }
580
    return false;
×
581
}
9✔
582

583
bool SystemImpl::has_gimbal() const
×
584
{
585
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
586
}
587

588
bool SystemImpl::send_message(mavlink_message_t& message)
×
589
{
590
    return _mavsdk_impl.send_message(message);
×
591
}
592

593
bool SystemImpl::queue_message(
883✔
594
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
595
{
596
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
883✔
597
}
598

599
void SystemImpl::send_autopilot_version_request()
59✔
600
{
601
    mavlink_request_message().request(
59✔
602
        MAVLINK_MSG_ID_AUTOPILOT_VERSION, MAV_COMP_ID_AUTOPILOT1, nullptr);
603
}
59✔
604

605
void SystemImpl::set_connected()
378✔
606
{
607
    bool enable_needed = false;
378✔
608
    {
609
        if (!_connected) {
378✔
610
            {
611
                std::lock_guard<std::mutex> lock(_components_mutex);
142✔
612
                if (!_components.empty()) {
142✔
613
                    LogDebug() << "Discovered " << _components.size() << " component(s)";
142✔
614
                }
615
            }
142✔
616

617
            _connected = true;
142✔
618

619
            // Only send heartbeats if we're not shutting down
620
            if (!_should_exit) {
142✔
621
                // We call this later to avoid deadlocks on creating the server components.
622
                _mavsdk_impl.call_user_callback([this]() {
284✔
623
                    // Send a heartbeat back immediately.
624
                    _mavsdk_impl.start_sending_heartbeats();
625
                });
626
            }
627

628
            _heartbeat_timeout_cookie =
142✔
629
                register_timeout_handler([this] { heartbeats_timed_out(); }, HEARTBEAT_TIMEOUT_S);
147✔
630

631
            enable_needed = true;
142✔
632

633
            // Queue callbacks without holding any locks to avoid deadlocks
634
            _is_connected_callbacks.queue(
142✔
635
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
636

637
        } else if (_connected) {
234✔
638
            refresh_timeout_handler(_heartbeat_timeout_cookie);
237✔
639
        }
640
        // If not yet connected there is nothing to do
641
    }
642

643
    if (enable_needed) {
379✔
644
        // Notify about the new system without holding any locks
645
        _mavsdk_impl.notify_on_discover();
142✔
646

647
        if (has_autopilot()) {
142✔
648
            send_autopilot_version_request();
59✔
649
        }
650

651
        // Enable plugins
652
        std::vector<PluginImplBase*> plugin_impls_to_enable;
142✔
653
        {
654
            std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
142✔
655
            plugin_impls_to_enable = _plugin_impls;
142✔
656
        }
142✔
657

658
        for (auto plugin_impl : plugin_impls_to_enable) {
144✔
659
            plugin_impl->enable();
2✔
660
        }
661
    }
142✔
662
}
379✔
663

664
void SystemImpl::set_disconnected()
5✔
665
{
666
    {
667
        // This might not be needed because this is probably called from the triggered
668
        // timeout anyway, but it should also do no harm.
669
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
670
        //_heartbeat_timeout_cookie = nullptr;
671

672
        _connected = false;
5✔
673
        _is_connected_callbacks.queue(
5✔
674
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
675
    }
676
    _mavsdk_impl.notify_on_timeout();
5✔
677

678
    _mavsdk_impl.stop_sending_heartbeats();
5✔
679

680
    {
681
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
5✔
682
        for (auto plugin_impl : _plugin_impls) {
7✔
683
            plugin_impl->disable();
2✔
684
        }
685
    }
5✔
686
}
5✔
687

688
uint8_t SystemImpl::get_system_id() const
827✔
689
{
690
    return _target_address.system_id;
827✔
691
}
692

693
std::vector<uint8_t> SystemImpl::component_ids() const
12✔
694
{
695
    std::lock_guard<std::mutex> lock(_components_mutex);
12✔
696
    return std::vector<uint8_t>{_components.begin(), _components.end()};
12✔
697
}
12✔
698

699
void SystemImpl::set_system_id(uint8_t system_id)
×
700
{
701
    _target_address.system_id = system_id;
×
702
}
×
703

704
uint8_t SystemImpl::get_own_system_id() const
1,471✔
705
{
706
    return _mavsdk_impl.get_own_system_id();
1,471✔
707
}
708

709
uint8_t SystemImpl::get_own_component_id() const
1,451✔
710
{
711
    return _mavsdk_impl.get_own_component_id();
1,451✔
712
}
713

714
MAV_TYPE SystemImpl::get_vehicle_type() const
×
715
{
716
    return _vehicle_type;
×
717
}
718

719
Vehicle SystemImpl::vehicle() const
×
720
{
721
    return to_vehicle_from_mav_type(_vehicle_type);
×
722
}
723

724
uint8_t SystemImpl::get_own_mav_type() const
×
725
{
726
    return _mavsdk_impl.get_mav_type();
×
727
}
728

729
MavlinkParameterClient::Result SystemImpl::set_param(
×
730
    const std::string& name,
731
    ParamValue value,
732
    std::optional<uint8_t> maybe_component_id,
733
    bool extended)
734
{
735
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
736
        ->set_param(name, value);
×
737
}
738

739
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
740
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
741
{
742
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
743
        ->set_param_float(name, value);
4✔
744
}
745

746
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
747
    const std::string& name,
748
    int32_t value,
749
    std::optional<uint8_t> maybe_component_id,
750
    bool extended)
751
{
752
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
753
        ->set_param_int(name, value);
4✔
754
}
755

756
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
757
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
758
{
759
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
760
        ->set_param_custom(name, value);
4✔
761
}
762

763
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
764
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
765
{
766
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
767
        ->get_all_params();
8✔
768
}
769

770
void SystemImpl::set_param_async(
3✔
771
    const std::string& name,
772
    ParamValue value,
773
    const SetParamCallback& callback,
774
    const void* cookie,
775
    std::optional<uint8_t> maybe_component_id,
776
    bool extended)
777
{
778
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
3✔
779
        ->set_param_async(name, value, callback, cookie);
6✔
780
}
3✔
781

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

794
void SystemImpl::set_param_int_async(
×
795
    const std::string& name,
796
    int32_t value,
797
    const SetParamCallback& callback,
798
    const void* cookie,
799
    std::optional<uint8_t> maybe_component_id,
800
    bool extended)
801
{
802
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
803
        ->set_param_int_async(name, value, callback, cookie);
×
804
}
×
805

806
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
5✔
807
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
808
{
809
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
810
        ->get_param_float(name);
10✔
811
}
812

813
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
814
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
815
{
816
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
817
        ->get_param_int(name);
10✔
818
}
819

820
std::pair<MavlinkParameterClient::Result, std::string>
821
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
822
{
823
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
824
        ->get_param_custom(name);
8✔
825
}
826

827
void SystemImpl::get_param_async(
×
828
    const std::string& name,
829
    ParamValue value,
830
    const GetParamAnyCallback& callback,
831
    const void* cookie,
832
    std::optional<uint8_t> maybe_component_id,
833
    bool extended)
834
{
835
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
836
        ->get_param_async(name, value, callback, cookie);
×
837
}
×
838

839
void SystemImpl::get_param_float_async(
×
840
    const std::string& name,
841
    const GetParamFloatCallback& callback,
842
    const void* cookie,
843
    std::optional<uint8_t> maybe_component_id,
844
    bool extended)
845
{
846
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
847
        ->get_param_float_async(name, callback, cookie);
×
848
}
×
849

850
void SystemImpl::get_param_int_async(
×
851
    const std::string& name,
852
    const GetParamIntCallback& callback,
853
    const void* cookie,
854
    std::optional<uint8_t> maybe_component_id,
855
    bool extended)
856
{
857
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
858
        ->get_param_int_async(name, callback, cookie);
×
859
}
×
860

861
void SystemImpl::get_param_custom_async(
×
862
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
863
{
864
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
865
}
×
866

867
void SystemImpl::cancel_all_param(const void* cookie)
9✔
868
{
869
    UNUSED(cookie);
9✔
870
    // FIXME: this currently crashes on destruction
871
    // param_sender(1, false)->cancel_all_param(cookie);
872
}
9✔
873

874
MavlinkCommandSender::Result
875
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
876
{
877
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
878
        make_command_flight_mode(system_mode, component_id);
×
879

880
    if (result.first != MavlinkCommandSender::Result::Success) {
×
881
        return result.first;
×
882
    }
883

884
    return send_command(result.second);
×
885
}
886

887
void SystemImpl::set_flight_mode_async(
×
888
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
889
{
890
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
891
        make_command_flight_mode(system_mode, component_id);
×
892

893
    if (result.first != MavlinkCommandSender::Result::Success) {
×
894
        if (callback) {
×
895
            callback(result.first, NAN);
×
896
        }
897
        return;
×
898
    }
899

900
    send_command_async(result.second, callback);
×
901
}
902

903
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
904
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
905
{
906
    if (_autopilot == Autopilot::ArduPilot) {
×
907
        return make_command_ardupilot_mode(flight_mode, component_id);
×
908
    } else {
909
        return make_command_px4_mode(flight_mode, component_id);
×
910
    }
911
}
912

913
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
914
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
915
{
916
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
917
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
918
    const uint8_t mode_type =
×
919
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
920

921
    MavlinkCommandSender::CommandLong command{};
×
922

923
    command.command = MAV_CMD_DO_SET_MODE;
×
924
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
925

926
    switch (_vehicle_type) {
×
927
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
928
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER: {
929
            const auto new_mode = flight_mode_to_ardupilot_rover_mode(flight_mode);
×
930
            if (new_mode == ardupilot::RoverMode::Unknown) {
×
931
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
932
                MavlinkCommandSender::CommandLong empty_command{};
×
933
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
934
            } else {
935
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
936
            }
937
            break;
×
938
        }
939
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
940
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
941
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
942
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
943
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
944
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
945
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
946
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
947
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
948
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
949
                MavlinkCommandSender::CommandLong empty_command{};
×
950
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
951
            } else {
952
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
953
            }
954
            break;
×
955
        }
956

957
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
958
        case MAV_TYPE::MAV_TYPE_COAXIAL:
959
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
960
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
961
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
962
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
963
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
964
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
965
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
966
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
967
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
968
                MavlinkCommandSender::CommandLong empty_command{};
×
969
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
970
            } else {
971
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
972
            }
973
            break;
×
974
        }
975

976
        default:
×
977
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
978
                     << _vehicle_type;
×
979
            MavlinkCommandSender::CommandLong empty_command{};
×
980
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
981
    }
982
    command.target_component_id = component_id;
×
983

984
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
985
}
986
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
987
{
988
    switch (flight_mode) {
×
989
        case FlightMode::Mission:
×
990
            return ardupilot::RoverMode::Auto;
×
991
        case FlightMode::Acro:
×
992
            return ardupilot::RoverMode::Acro;
×
993
        case FlightMode::Hold:
×
994
            return ardupilot::RoverMode::Hold;
×
995
        case FlightMode::ReturnToLaunch:
×
996
            return ardupilot::RoverMode::RTL;
×
997
        case FlightMode::Manual:
×
998
            return ardupilot::RoverMode::Manual;
×
999
        case FlightMode::FollowMe:
×
1000
            return ardupilot::RoverMode::Follow;
×
1001
        case FlightMode::Offboard:
×
1002
            return ardupilot::RoverMode::Guided;
×
1003
        case FlightMode::Unknown:
×
1004
        case FlightMode::Ready:
1005
        case FlightMode::Takeoff:
1006
        case FlightMode::Land:
1007
        case FlightMode::Altctl:
1008
        case FlightMode::Posctl:
1009
        case FlightMode::Rattitude:
1010
        case FlightMode::Stabilized:
1011
        default:
1012
            return ardupilot::RoverMode::Unknown;
×
1013
    }
1014
}
1015
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
1016
{
1017
    switch (flight_mode) {
×
1018
        case FlightMode::Mission:
×
1019
            return ardupilot::CopterMode::Auto;
×
1020
        case FlightMode::Acro:
×
1021
            return ardupilot::CopterMode::Acro;
×
1022
        case FlightMode::Hold:
×
1023
            return ardupilot::CopterMode::Loiter;
×
1024
        case FlightMode::ReturnToLaunch:
×
1025
            return ardupilot::CopterMode::Rtl;
×
1026
        case FlightMode::Land:
×
1027
            return ardupilot::CopterMode::Land;
×
1028
        case FlightMode::Manual:
×
1029
            return ardupilot::CopterMode::Stabilize;
×
1030
        case FlightMode::FollowMe:
×
1031
            return ardupilot::CopterMode::Follow;
×
1032
        case FlightMode::Offboard:
×
1033
            return ardupilot::CopterMode::Guided;
×
1034
        case FlightMode::Altctl:
×
1035
            return ardupilot::CopterMode::AltHold;
×
1036
        case FlightMode::Posctl:
×
1037
            return ardupilot::CopterMode::PosHold;
×
1038
        case FlightMode::Stabilized:
×
1039
            return ardupilot::CopterMode::Stabilize;
×
1040
        case FlightMode::Unknown:
×
1041
        case FlightMode::Ready:
1042
        case FlightMode::Takeoff:
1043
        case FlightMode::Rattitude:
1044
        default:
1045
            return ardupilot::CopterMode::Unknown;
×
1046
    }
1047
}
1048
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
1049
{
1050
    switch (flight_mode) {
×
1051
        case FlightMode::Mission:
×
1052
            return ardupilot::PlaneMode::Auto;
×
1053
        case FlightMode::Acro:
×
1054
            return ardupilot::PlaneMode::Acro;
×
1055
        case FlightMode::Hold:
×
1056
            return ardupilot::PlaneMode::Loiter;
×
1057
        case FlightMode::ReturnToLaunch:
×
1058
            return ardupilot::PlaneMode::Rtl;
×
1059
        case FlightMode::Manual:
×
1060
            return ardupilot::PlaneMode::Manual;
×
1061
        case FlightMode::FBWA:
×
1062
            return ardupilot::PlaneMode::Fbwa;
×
1063
        case FlightMode::FBWB:
×
1064
            return ardupilot::PlaneMode::Fbwb;
×
1065
        case FlightMode::Stabilized:
×
1066
            return ardupilot::PlaneMode::Stabilize;
×
1067
        case FlightMode::Takeoff:
×
1068
            return ardupilot::PlaneMode::Takeoff;
×
1069
        case FlightMode::Offboard:
×
1070
            return ardupilot::PlaneMode::Guided;
×
1071
        case FlightMode::Unknown:
×
1072
            return ardupilot::PlaneMode::Unknown;
×
1073
        default:
×
1074
            return ardupilot::PlaneMode::Unknown;
×
1075
    }
1076
}
1077

1078
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
1079
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
1080
{
1081
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1082
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1083

1084
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1085

1086
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1087
    //       but want to be rather safe than sorry.
1088
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1089
    uint8_t custom_sub_mode = 0;
×
1090

1091
    switch (flight_mode) {
×
1092
        case FlightMode::Hold:
×
1093
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
1094
            break;
×
1095
        case FlightMode::ReturnToLaunch:
×
1096
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
1097
            break;
×
1098
        case FlightMode::Takeoff:
×
1099
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
1100
            break;
×
1101
        case FlightMode::Land:
×
1102
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
1103
            break;
×
1104
        case FlightMode::Mission:
×
1105
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
1106
            break;
×
1107
        case FlightMode::FollowMe:
×
1108
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
1109
            break;
×
1110
        case FlightMode::Offboard:
×
1111
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
1112
            break;
×
1113
        case FlightMode::Manual:
×
1114
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
1115
            break;
×
1116
        case FlightMode::Posctl:
×
1117
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
1118
            break;
×
1119
        case FlightMode::Altctl:
×
1120
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
1121
            break;
×
1122
        case FlightMode::Rattitude:
×
1123
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
1124
            break;
×
1125
        case FlightMode::Acro:
×
1126
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1127
            break;
×
1128
        case FlightMode::Stabilized:
×
1129
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1130
            break;
×
1131
        default:
×
1132
            LogErr() << "Unknown Flight mode.";
×
1133
            MavlinkCommandSender::CommandLong empty_command{};
×
1134
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1135
    }
1136

1137
    MavlinkCommandSender::CommandLong command{};
×
1138

1139
    command.command = MAV_CMD_DO_SET_MODE;
×
1140
    command.params.maybe_param1 = static_cast<float>(mode);
×
1141
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1142
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1143
    command.target_component_id = component_id;
×
1144

1145
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1146
}
1147

1148
FlightMode SystemImpl::get_flight_mode() const
11✔
1149
{
1150
    return _flight_mode;
11✔
1151
}
1152

1153
void SystemImpl::receive_float_param(
×
1154
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1155
{
1156
    if (callback) {
×
1157
        if (result == MavlinkParameterClient::Result::Success) {
×
1158
            callback(result, value.get<float>());
×
1159
        } else {
1160
            callback(result, NAN);
×
1161
        }
1162
    }
1163
}
×
1164

1165
void SystemImpl::receive_int_param(
×
1166
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1167
{
1168
    if (callback) {
×
1169
        if (result == MavlinkParameterClient::Result::Success) {
×
1170
            callback(result, value.get<int32_t>());
×
1171
        } else {
1172
            callback(result, 0);
×
1173
        }
1174
    }
1175
}
×
1176

1177
uint8_t SystemImpl::get_autopilot_id() const
296✔
1178
{
1179
    std::lock_guard<std::mutex> lock(_components_mutex);
296✔
1180
    for (auto compid : _components)
393✔
1181
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
303✔
1182
            return compid;
206✔
1183
        }
1184
    // FIXME: Not sure what should be returned if autopilot is not found
1185
    return uint8_t(0);
90✔
1186
}
296✔
1187

1188
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1189
{
1190
    std::lock_guard<std::mutex> lock(_components_mutex);
×
1191
    std::vector<uint8_t> camera_ids{};
×
1192

1193
    for (auto compid : _components)
×
1194
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1195
            camera_ids.push_back(compid);
×
1196
        }
1197
    return camera_ids;
×
1198
}
×
1199

1200
uint8_t SystemImpl::get_gimbal_id() const
×
1201
{
1202
    std::lock_guard<std::mutex> lock(_components_mutex);
×
1203
    for (auto compid : _components)
×
1204
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1205
            return compid;
×
1206
        }
1207
    return uint8_t(0);
×
1208
}
×
1209

1210
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
5✔
1211
{
1212
    {
1213
        std::lock_guard<std::mutex> lock(_components_mutex);
5✔
1214
        if (_target_address.system_id == 0 && _components.empty()) {
5✔
1215
            return MavlinkCommandSender::Result::NoSystem;
×
1216
        }
1217
    }
5✔
1218
    command.target_system_id = get_system_id();
5✔
1219
    return _command_sender.send_command(command);
5✔
1220
}
1221

1222
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1223
{
1224
    {
1225
        std::lock_guard<std::mutex> lock(_components_mutex);
×
1226
        if (_target_address.system_id == 0 && _components.empty()) {
×
1227
            return MavlinkCommandSender::Result::NoSystem;
×
1228
        }
1229
    }
×
1230
    command.target_system_id = get_system_id();
×
1231
    return _command_sender.send_command(command);
×
1232
}
1233

1234
void SystemImpl::send_command_async(
7✔
1235
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1236
{
1237
    {
1238
        std::lock_guard<std::mutex> lock(_components_mutex);
7✔
1239
        if (_target_address.system_id == 0 && _components.empty()) {
7✔
1240
            if (callback) {
×
1241
                callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1242
            }
1243
            return;
×
1244
        }
1245
    }
7✔
1246
    command.target_system_id = get_system_id();
7✔
1247

1248
    _command_sender.queue_command_async(command, callback);
7✔
1249
}
1250

1251
void SystemImpl::send_command_async(
×
1252
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1253
{
1254
    {
1255
        std::lock_guard<std::mutex> lock(_components_mutex);
×
1256
        if (_target_address.system_id == 0 && _components.empty()) {
×
1257
            if (callback) {
×
1258
                callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1259
            }
1260
            return;
×
1261
        }
1262
    }
×
1263
    command.target_system_id = get_system_id();
×
1264

1265
    _command_sender.queue_command_async(command, callback);
×
1266
}
1267

1268
MavlinkCommandSender::Result
1269
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1270
{
1271
    MavlinkCommandSender::CommandLong command =
1272
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1273
    return send_command(command);
×
1274
}
1275

1276
void SystemImpl::set_msg_rate_async(
1✔
1277
    uint16_t message_id,
1278
    double rate_hz,
1279
    const CommandResultCallback& callback,
1280
    uint8_t component_id)
1281
{
1282
    MavlinkCommandSender::CommandLong command =
1283
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1284
    send_command_async(command, callback);
1✔
1285
}
1✔
1286

1287
MavlinkCommandSender::CommandLong
1288
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1289
{
1290
    MavlinkCommandSender::CommandLong command{};
1✔
1291

1292
    // 0 to request default rate, -1 to stop stream
1293

1294
    float interval_us = 0.0f;
1✔
1295

1296
    if (rate_hz > 0) {
1✔
1297
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1298
    } else if (rate_hz < 0) {
×
1299
        interval_us = -1.0f;
×
1300
    }
1301

1302
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1303
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1304
    command.params.maybe_param2 = interval_us;
1✔
1305
    command.target_component_id = component_id;
1✔
1306

1307
    return command;
1✔
1308
}
1309

1310
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
80✔
1311
{
1312
    assert(plugin_impl);
80✔
1313

1314
    plugin_impl->init();
80✔
1315

1316
    {
1317
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
80✔
1318
        _plugin_impls.push_back(plugin_impl);
80✔
1319
    }
80✔
1320

1321
    // If we're connected already, let's enable it straightaway.
1322
    if (_connected) {
80✔
1323
        plugin_impl->enable();
80✔
1324
    }
1325
}
80✔
1326

1327
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
80✔
1328
{
1329
    assert(plugin_impl);
80✔
1330

1331
    plugin_impl->disable();
80✔
1332
    plugin_impl->deinit();
80✔
1333

1334
    // Remove first, so it won't get enabled/disabled anymore.
1335
    {
1336
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
80✔
1337
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
80✔
1338
        if (found != _plugin_impls.end()) {
80✔
1339
            _plugin_impls.erase(found);
80✔
1340
        }
1341
    }
80✔
1342
}
80✔
1343

1344
void SystemImpl::call_user_callback_located(
1,007✔
1345
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1346
{
1347
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
1,007✔
1348
}
1,007✔
1349

1350
void SystemImpl::param_changed(const std::string& name)
×
1351
{
1352
    for (auto& callback : _param_changed_callbacks) {
×
1353
        callback.second(name);
×
1354
    }
1355
}
×
1356

1357
void SystemImpl::register_param_changed_handler(
×
1358
    const ParamChangedCallback& callback, const void* cookie)
1359
{
1360
    if (!callback) {
×
1361
        LogErr() << "No callback for param_changed_handler supplied.";
×
1362
        return;
×
1363
    }
1364

1365
    if (!cookie) {
×
1366
        LogErr() << "No callback for param_changed_handler supplied.";
×
1367
        return;
×
1368
    }
1369

1370
    _param_changed_callbacks[cookie] = callback;
×
1371
}
1372

1373
void SystemImpl::unregister_param_changed_handler(const void* cookie)
×
1374
{
1375
    auto it = _param_changed_callbacks.find(cookie);
×
1376
    if (it == _param_changed_callbacks.end()) {
×
1377
        LogWarn() << "param_changed_handler for cookie not found";
×
1378
        return;
×
1379
    }
1380
    _param_changed_callbacks.erase(it);
×
1381
}
1382

1383
Time& SystemImpl::get_time()
507✔
1384
{
1385
    return _mavsdk_impl.time;
507✔
1386
}
1387

1388
void SystemImpl::subscribe_param_float(
×
1389
    const std::string& name,
1390
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1391
    const void* cookie)
1392
{
1393
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1394
}
×
1395

1396
void SystemImpl::subscribe_param_int(
×
1397
    const std::string& name,
1398
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1399
    const void* cookie)
1400
{
1401
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1402
}
×
1403
void SystemImpl::subscribe_param_custom(
×
1404
    const std::string& name,
1405
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1406
    const void* cookie)
1407
{
1408
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1409
}
×
1410

1411
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
85✔
1412
{
1413
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
85✔
1414

1415
    for (auto& entry : _mavlink_parameter_clients) {
87✔
1416
        if (entry.component_id == component_id && entry.extended == extended) {
77✔
1417
            return entry.parameter_client.get();
75✔
1418
        }
1419
    }
1420

1421
    _mavlink_parameter_clients.push_back(
10✔
1422
        {std::make_unique<MavlinkParameterClient>(
1423
             _mavsdk_impl.default_server_component_impl().sender(),
10✔
1424
             _mavlink_message_handler,
10✔
1425
             _mavsdk_impl.timeout_handler,
10✔
1426
             [this]() { return timeout_s(); },
70✔
1427
             [this]() { return autopilot(); },
34✔
1428
             get_system_id(),
10✔
1429
             component_id,
1430
             extended),
1431
         component_id,
1432
         extended});
1433

1434
    return _mavlink_parameter_clients.back().parameter_client.get();
10✔
1435
}
85✔
1436

1437
std::vector<Connection*> SystemImpl::get_connections() const
×
1438
{
1439
    return _mavsdk_impl.get_connections();
×
1440
}
1441

1442
mav::MessageSet& SystemImpl::get_message_set() const
23✔
1443
{
1444
    return _mavsdk_impl.get_message_set();
23✔
1445
}
1446

1447
bool SystemImpl::load_custom_xml_to_message_set(const std::string& xml_content)
6✔
1448
{
1449
    return _mavsdk_impl.load_custom_xml_to_message_set(xml_content);
6✔
1450
}
1451

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

© 2026 Coveralls, Inc