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

mavlink / MAVSDK / 20513670813

26 Dec 2025 01:20AM UTC coverage: 48.078% (-0.02%) from 48.097%
20513670813

push

github

web-flow
Merge pull request #2744 from mavlink/pr-example-fixup-hz

examples: fixup rate calculation in sniffer

17745 of 36909 relevant lines covered (48.08%)

464.57 hits per line

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

72.21
/src/mavsdk/core/mavsdk_impl.cpp
1
#include "mavsdk_impl.h"
2

3
#include <algorithm>
4
#include <mutex>
5
#include <tcp_server_connection.h>
6

7
#include "connection.h"
8
#include "log.h"
9
#include "tcp_client_connection.h"
10
#include "tcp_server_connection.h"
11
#include "udp_connection.h"
12
#include "raw_connection.h"
13
#include "system.h"
14
#include "system_impl.h"
15
#include "serial_connection.h"
16
#include "version.h"
17
#include "server_component_impl.h"
18
#include "overloaded.h"
19
#include "mavlink_channels.h"
20
#include "callback_list.tpp"
21
#include "hostname_to_ip.h"
22
#include "embedded_mavlink_xml.h"
23
#include <mav/MessageSet.h>
24

25
namespace mavsdk {
26

27
template class CallbackList<>;
28

29
MavsdkImpl::MavsdkImpl(const Mavsdk::Configuration& configuration) :
138✔
30
    timeout_handler(time),
138✔
31
    call_every_handler(time)
276✔
32
{
33
    LogInfo() << "MAVSDK version: " << mavsdk_version;
138✔
34

35
    if (const char* env_p = std::getenv("MAVSDK_CALLBACK_DEBUGGING")) {
138✔
36
        if (std::string(env_p) == "1") {
×
37
            LogDebug() << "Callback debugging is on.";
×
38
            _callback_debugging = true;
×
39
            _callback_tracker = std::make_unique<CallbackTracker>();
×
40
        }
41
    }
42

43
    if (const char* env_p = std::getenv("MAVSDK_MESSAGE_DEBUGGING")) {
138✔
44
        if (std::string(env_p) == "1") {
×
45
            LogDebug() << "Message debugging is on.";
×
46
            _message_logging_on = true;
×
47
        }
48
    }
49

50
    if (const char* env_p = std::getenv("MAVSDK_SYSTEM_DEBUGGING")) {
138✔
51
        if (std::string(env_p) == "1") {
×
52
            LogDebug() << "System debugging is on.";
×
53
            _system_debugging = true;
×
54
        }
55
    }
56

57
    set_configuration(configuration);
138✔
58

59
    // Initialize MessageSet with embedded XML content in dependency order
60
    // This happens at startup before any connections are created, so no synchronization needed
61
    _message_set = std::make_unique<mav::MessageSet>();
138✔
62
    _message_set->addFromXMLString(mav_embedded::MINIMAL_XML);
138✔
63
    _message_set->addFromXMLString(mav_embedded::STANDARD_XML);
138✔
64
    _message_set->addFromXMLString(mav_embedded::COMMON_XML);
138✔
65
    _message_set->addFromXMLString(mav_embedded::ARDUPILOTMEGA_XML);
138✔
66

67
    // Initialize BufferParser for thread-safe parsing
68
    _buffer_parser = std::make_unique<mav::BufferParser>(*_message_set);
138✔
69

70
    // Start the user callback thread first, so it is ready for anything generated by
71
    // the work thread.
72

73
    _process_user_callbacks_thread =
276✔
74
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
138✔
75

76
    _work_thread = new std::thread(&MavsdkImpl::work_thread, this);
138✔
77
}
138✔
78

79
MavsdkImpl::~MavsdkImpl()
138✔
80
{
81
    {
82
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
138✔
83
        call_every_handler.remove(_heartbeat_send_cookie);
138✔
84
    }
138✔
85

86
    _should_exit = true;
138✔
87

88
    // Stop work first because we don't want to trigger anything that would
89
    // potentially want to call into user code.
90

91
    if (_work_thread != nullptr) {
138✔
92
        _work_thread->join();
138✔
93
        delete _work_thread;
138✔
94
        _work_thread = nullptr;
138✔
95
    }
96

97
    if (_process_user_callbacks_thread != nullptr) {
138✔
98
        _user_callback_queue.stop();
138✔
99
        _process_user_callbacks_thread->join();
138✔
100
        delete _process_user_callbacks_thread;
138✔
101
        _process_user_callbacks_thread = nullptr;
138✔
102
    }
103

104
    std::lock_guard lock(_mutex);
138✔
105

106
    _systems.clear();
138✔
107
    _connections.clear();
138✔
108
}
138✔
109

110
std::string MavsdkImpl::version()
1✔
111
{
112
    static unsigned version_counter = 0;
113

114
    ++version_counter;
1✔
115

116
    switch (version_counter) {
1✔
117
        case 10:
×
118
            return "You were wondering about the name of this library?";
×
119
        case 11:
×
120
            return "Let's look at the history:";
×
121
        case 12:
×
122
            return "DroneLink";
×
123
        case 13:
×
124
            return "DroneCore";
×
125
        case 14:
×
126
            return "DronecodeSDK";
×
127
        case 15:
×
128
            return "MAVSDK";
×
129
        case 16:
×
130
            return "And that's it...";
×
131
        case 17:
×
132
            return "At least for now ¯\\_(ツ)_/¯.";
×
133
        default:
1✔
134
            return mavsdk_version;
1✔
135
    }
136
}
137

138
std::vector<std::shared_ptr<System>> MavsdkImpl::systems() const
177✔
139
{
140
    std::vector<std::shared_ptr<System>> systems_result{};
177✔
141

142
    std::lock_guard lock(_mutex);
177✔
143
    for (auto& system : _systems) {
280✔
144
        // We ignore the 0 entry because it's just a null system.
145
        // It's only created because the older, deprecated API needs a
146
        // reference.
147
        if (system.first == 0) {
103✔
148
            continue;
×
149
        }
150
        systems_result.push_back(system.second);
103✔
151
    }
152

153
    return systems_result;
177✔
154
}
177✔
155

156
std::optional<std::shared_ptr<System>> MavsdkImpl::first_autopilot(double timeout_s)
57✔
157
{
158
    {
159
        std::lock_guard lock(_mutex);
57✔
160
        for (auto system : _systems) {
58✔
161
            if (system.second->is_connected() && system.second->has_autopilot()) {
4✔
162
                return system.second;
3✔
163
            }
164
        }
4✔
165
    }
57✔
166

167
    if (timeout_s == 0.0) {
54✔
168
        // Don't wait at all.
169
        return {};
×
170
    }
171

172
    auto prom = std::make_shared<std::promise<std::shared_ptr<System>>>();
54✔
173
    auto fut = prom->get_future();
54✔
174

175
    auto flag = std::make_shared<std::once_flag>();
54✔
176
    auto handle = subscribe_on_new_system([this, prom, flag]() {
54✔
177
        // Check all systems, not just the first one
178
        auto all_systems = systems();
55✔
179
        for (auto& system : all_systems) {
57✔
180
            if (system->is_connected() && system->has_autopilot()) {
56✔
181
                std::call_once(*flag, [prom, system]() { prom->set_value(system); });
108✔
182
                break;
54✔
183
            }
184
        }
185
    });
55✔
186

187
    if (timeout_s > 0.0) {
54✔
188
        if (fut.wait_for(std::chrono::milliseconds(int64_t(timeout_s * 1e3))) ==
54✔
189
            std::future_status::ready) {
190
            unsubscribe_on_new_system(handle);
54✔
191
            return fut.get();
54✔
192

193
        } else {
194
            unsubscribe_on_new_system(handle);
×
195
            return std::nullopt;
×
196
        }
197
    } else {
198
        fut.wait();
×
199
        unsubscribe_on_new_system(handle);
×
200
        return std::optional(fut.get());
×
201
    }
202
}
54✔
203

204
std::shared_ptr<ServerComponent> MavsdkImpl::server_component(unsigned instance)
54✔
205
{
206
    std::lock_guard lock(_mutex);
54✔
207

208
    auto component_type = _configuration.get_component_type();
54✔
209
    switch (component_type) {
54✔
210
        case ComponentType::Autopilot:
54✔
211
        case ComponentType::GroundStation:
212
        case ComponentType::CompanionComputer:
213
        case ComponentType::Camera:
214
        case ComponentType::Gimbal:
215
        case ComponentType::RemoteId:
216
        case ComponentType::Custom:
217
            return server_component_by_type(component_type, instance);
54✔
218
        default:
×
219
            LogErr() << "Unknown component type";
×
220
            return {};
×
221
    }
222
}
54✔
223

224
std::shared_ptr<ServerComponent>
225
MavsdkImpl::server_component_by_type(ComponentType server_component_type, unsigned instance)
54✔
226
{
227
    switch (server_component_type) {
54✔
228
        case ComponentType::Autopilot:
40✔
229
            if (instance == 0) {
40✔
230
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1);
40✔
231
            } else {
232
                LogErr() << "Only autopilot instance 0 is valid";
×
233
                return {};
×
234
            }
235

236
        case ComponentType::GroundStation:
×
237
            if (instance == 0) {
×
238
                return server_component_by_id(MAV_COMP_ID_MISSIONPLANNER);
×
239
            } else {
240
                LogErr() << "Only one ground station supported at this time";
×
241
                return {};
×
242
            }
243

244
        case ComponentType::CompanionComputer:
1✔
245
            if (instance == 0) {
1✔
246
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER);
1✔
247
            } else if (instance == 1) {
×
248
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER2);
×
249
            } else if (instance == 2) {
×
250
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER3);
×
251
            } else if (instance == 3) {
×
252
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER4);
×
253
            } else {
254
                LogErr() << "Only companion computer 0..3 are supported";
×
255
                return {};
×
256
            }
257

258
        case ComponentType::Camera:
13✔
259
            if (instance == 0) {
13✔
260
                return server_component_by_id(MAV_COMP_ID_CAMERA);
13✔
261
            } else if (instance == 1) {
×
262
                return server_component_by_id(MAV_COMP_ID_CAMERA2);
×
263
            } else if (instance == 2) {
×
264
                return server_component_by_id(MAV_COMP_ID_CAMERA3);
×
265
            } else if (instance == 3) {
×
266
                return server_component_by_id(MAV_COMP_ID_CAMERA4);
×
267
            } else if (instance == 4) {
×
268
                return server_component_by_id(MAV_COMP_ID_CAMERA5);
×
269
            } else if (instance == 5) {
×
270
                return server_component_by_id(MAV_COMP_ID_CAMERA6);
×
271
            } else {
272
                LogErr() << "Only camera 0..5 are supported";
×
273
                return {};
×
274
            }
275

276
        default:
×
277
            LogErr() << "Unknown server component type";
×
278
            return {};
×
279
    }
280
}
281

282
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id(uint8_t component_id)
54✔
283
{
284
    if (component_id == 0) {
54✔
285
        LogErr() << "Server component with component ID 0 not allowed";
×
286
        return nullptr;
×
287
    }
288

289
    std::lock_guard lock(_server_components_mutex);
54✔
290

291
    return server_component_by_id_with_lock(component_id);
54✔
292
}
54✔
293

294
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id_with_lock(uint8_t component_id)
261✔
295
{
296
    for (auto& it : _server_components) {
262✔
297
        if (it.first == component_id) {
123✔
298
            if (it.second != nullptr) {
122✔
299
                return it.second;
122✔
300
            } else {
301
                it.second = std::make_shared<ServerComponent>(*this, component_id);
×
302
            }
303
        }
304
    }
305

306
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
139✔
307
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
278✔
308

309
    return _server_components.back().second;
139✔
310
}
311

312
void MavsdkImpl::forward_message(mavlink_message_t& message, Connection* connection)
47✔
313
{
314
    // Forward_message Function implementing Mavlink routing rules.
315
    // See https://mavlink.io/en/guide/routing.html
316

317
    bool forward_heartbeats_enabled = true;
47✔
318
    const uint8_t target_system_id = get_target_system_id(message);
47✔
319
    const uint8_t target_component_id = get_target_component_id(message);
47✔
320

321
    // If it's a message only for us, we keep it, otherwise, we forward it.
322
    const bool targeted_only_at_us =
323
        (target_system_id == get_own_system_id() && target_component_id == get_own_component_id());
47✔
324

325
    // We don't forward heartbeats unless it's specifically enabled.
326
    const bool heartbeat_check_ok =
47✔
327
        (message.msgid != MAVLINK_MSG_ID_HEARTBEAT || forward_heartbeats_enabled);
47✔
328

329
    if (!targeted_only_at_us && heartbeat_check_ok) {
47✔
330
        unsigned successful_emissions = 0;
40✔
331
        for (auto& entry : _connections) {
117✔
332
            // Check whether the connection is not the one from which we received the message.
333
            // And also check if the connection was set to forward messages.
334
            if (entry.connection.get() == connection ||
114✔
335
                !entry.connection->should_forward_messages()) {
37✔
336
                continue;
40✔
337
            }
338
            auto result = (*entry.connection).send_message(message);
37✔
339
            if (result.first) {
37✔
340
                successful_emissions++;
36✔
341
            } else {
342
                _connections_errors_subscriptions.queue(
2✔
343
                    Mavsdk::ConnectionError{result.second, entry.handle},
1✔
344
                    [this](const auto& func) { call_user_callback(func); });
×
345
            }
346
        }
37✔
347
        if (successful_emissions == 0) {
40✔
348
            if (_system_debugging) {
4✔
349
                LogErr() << "Message forwarding failed";
×
350
            }
351
        }
352
    }
353
}
47✔
354

355
void MavsdkImpl::receive_message(
2,493✔
356
    MavlinkReceiver::ParseResult result, mavlink_message_t& message, Connection* connection)
357
{
358
    if (result == MavlinkReceiver::ParseResult::MessageParsed) {
2,493✔
359
        // Valid message: queue for full processing (which includes forwarding)
360
        {
361
            std::lock_guard lock(_received_messages_mutex);
2,490✔
362
            _received_messages.emplace(ReceivedMessage{std::move(message), connection});
2,498✔
363
        }
2,493✔
364
        _received_messages_cv.notify_one();
2,498✔
365

366
    } else if (result == MavlinkReceiver::ParseResult::BadCrc) {
3✔
367
        // Unknown message: forward only, don't process locally
368
        forward_message(message, connection);
4✔
369
    }
370
}
2,500✔
371

372
void MavsdkImpl::receive_libmav_message(
2,492✔
373
    const Mavsdk::MavlinkMessage& message, Connection* connection)
374
{
375
    {
376
        std::lock_guard lock(_received_libmav_messages_mutex);
2,492✔
377
        _received_libmav_messages.emplace(ReceivedLibmavMessage{message, connection});
2,501✔
378
    }
2,500✔
379
    _received_libmav_messages_cv.notify_one();
2,501✔
380
}
2,500✔
381

382
void MavsdkImpl::process_messages()
31,222✔
383
{
384
    std::lock_guard lock(_received_messages_mutex);
31,222✔
385
    while (!_received_messages.empty()) {
34,549✔
386
        auto message_copied = _received_messages.front();
2,481✔
387
        process_message(message_copied.message, message_copied.connection_ptr);
2,476✔
388
        _received_messages.pop();
2,479✔
389
    }
390
}
31,446✔
391

392
void MavsdkImpl::process_libmav_messages()
31,350✔
393
{
394
    std::lock_guard lock(_received_libmav_messages_mutex);
31,350✔
395
    while (!_received_libmav_messages.empty()) {
34,701✔
396
        auto message_copied = _received_libmav_messages.front();
2,481✔
397
        process_libmav_message(message_copied.message, message_copied.connection_ptr);
2,480✔
398
        _received_libmav_messages.pop();
2,479✔
399
    }
2,481✔
400
}
31,710✔
401

402
void MavsdkImpl::process_message(mavlink_message_t& message, Connection* connection)
2,477✔
403
{
404
    // Assumes _received_messages_mutex
405

406
    if (_message_logging_on) {
2,477✔
407
        LogDebug() << "Processing message " << message.msgid << " from "
×
408
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
409
    }
410

411
    if (_should_exit) {
2,477✔
412
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
413
        return;
×
414
    }
415

416
    {
417
        std::lock_guard lock(_mutex);
2,477✔
418

419
        /** @note: Forward message FIRST (before intercept) if option is enabled and multiple
420
         * interfaces are connected. This ensures that forwarded messages are not affected by
421
         * intercept modifications. Performs message forwarding checks for every messages if message
422
         * forwarding is enabled on at least one connection, and in case of a single forwarding
423
         * connection, we check that it is not the one which received the current message.
424
         *
425
         * Conditions:
426
         * 1. At least 2 connections.
427
         * 2. At least 1 forwarding connection.
428
         * 3. At least 2 forwarding connections or current connection is not forwarding.
429
         */
430

431
        if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
2,524✔
432
            (mavsdk::Connection::forwarding_connections_count() > 1 ||
43✔
433
             !connection->should_forward_messages())) {
434
            if (_message_logging_on) {
43✔
435
                LogDebug() << "Forwarding message " << message.msgid << " from "
×
436
                           << static_cast<int>(message.sysid) << "/"
×
437
                           << static_cast<int>(message.compid);
×
438
            }
439
            forward_message(message, connection);
43✔
440
        }
441

442
        if (_should_exit) {
2,478✔
443
            // If we're meant to clean up, let's not try to acquire any more locks but bail.
444
            return;
×
445
        }
446

447
        // This is a low level interface where incoming messages can be tampered
448
        // with or even dropped FOR LOCAL PROCESSING ONLY (after forwarding).
449
        {
450
            bool keep = true;
2,478✔
451
            {
452
                std::lock_guard<std::mutex> intercept_lock(_intercept_callbacks_mutex);
2,478✔
453
                if (_intercept_incoming_messages_callback != nullptr) {
2,481✔
454
                    keep = _intercept_incoming_messages_callback(message);
241✔
455
                }
456
            }
2,479✔
457

458
            if (!keep) {
2,481✔
459
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
32✔
460
                return;
31✔
461
            }
462
        }
463

464
        // Don't ever create a system with sysid 0.
465
        if (message.sysid == 0) {
2,449✔
466
            if (_message_logging_on) {
×
467
                LogDebug() << "Ignoring message with sysid == 0";
×
468
            }
469
            return;
×
470
        }
471

472
        // Filter out messages by QGroundControl, however, only do that if MAVSDK
473
        // is also implementing a ground station and not if it is used in another
474
        // configuration, e.g. on a companion.
475
        //
476
        // This is a workaround because PX4 started forwarding messages between
477
        // mavlink instances which leads to existing implementations (including
478
        // examples and integration tests) to connect to QGroundControl by accident
479
        // instead of PX4 because the check `has_autopilot()` is not used.
480

481
        if (_configuration.get_component_type() == ComponentType::GroundStation &&
2,449✔
482
            message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
2,448✔
483
            if (_message_logging_on) {
×
484
                LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
485
            }
486
            return;
×
487
        }
488

489
        bool found_system = false;
2,448✔
490
        for (auto& system : _systems) {
2,481✔
491
            if (system.first == message.sysid) {
2,346✔
492
                system.second->system_impl()->add_new_component(message.compid);
2,313✔
493
                found_system = true;
2,315✔
494
                break;
2,315✔
495
            }
496
        }
497

498
        if (!found_system) {
2,451✔
499
            if (_system_debugging) {
135✔
500
                LogWarn() << "Create new system/component " << (int)message.sysid << "/"
×
501
                          << (int)message.compid;
×
502
                LogWarn() << "From message " << (int)message.msgid << " with len "
×
503
                          << (int)message.len;
×
504
                std::string bytes = "";
×
505
                for (unsigned i = 0; i < 12 + message.len; ++i) {
×
506
                    bytes += std::to_string(reinterpret_cast<uint8_t*>(&message)[i]) + ' ';
×
507
                }
508
                LogWarn() << "Bytes: " << bytes;
×
509
            }
×
510
            make_system_with_component(message.sysid, message.compid);
135✔
511

512
            // We now better talk back.
513
            start_sending_heartbeats();
135✔
514
        }
515

516
        if (_should_exit) {
2,451✔
517
            // Don't try to call at() if systems have already been destroyed
518
            // in destructor.
519
            return;
×
520
        }
521
    }
2,479✔
522

523
    mavlink_message_handler.process_message(message);
2,450✔
524

525
    for (auto& system : _systems) {
2,483✔
526
        if (system.first == message.sysid) {
2,482✔
527
            system.second->system_impl()->process_mavlink_message(message);
2,448✔
528
            break;
2,450✔
529
        }
530
    }
531
}
532

533
void MavsdkImpl::process_libmav_message(
2,478✔
534
    const Mavsdk::MavlinkMessage& message, Connection* /* connection */)
535
{
536
    // Assumes _received_libmav_messages_mutex
537

538
    if (_message_logging_on) {
2,478✔
539
        LogDebug() << "MavsdkImpl::process_libmav_message: " << message.message_name << " from "
×
540
                   << static_cast<int>(message.system_id) << "/"
×
541
                   << static_cast<int>(message.component_id);
×
542
    }
543

544
    // JSON message interception for incoming messages
545
    if (!call_json_interception_callbacks(message, _incoming_json_message_subscriptions)) {
2,478✔
546
        // Message was dropped by interception callback
547
        if (_message_logging_on) {
×
548
            LogDebug() << "Incoming JSON message " << message.message_name
×
549
                       << " dropped by interception";
×
550
        }
551
        return;
×
552
    }
553

554
    if (_message_logging_on) {
2,479✔
555
        LogDebug() << "Processing libmav message " << message.message_name << " from "
×
556
                   << static_cast<int>(message.system_id) << "/"
×
557
                   << static_cast<int>(message.component_id);
×
558
    }
559

560
    if (_should_exit) {
2,479✔
561
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
562
        return;
×
563
    }
564

565
    {
566
        std::lock_guard lock(_mutex);
2,477✔
567

568
        // Don't ever create a system with sysid 0.
569
        if (message.system_id == 0) {
2,480✔
570
            if (_message_logging_on) {
×
571
                LogDebug() << "Ignoring libmav message with sysid == 0";
×
572
            }
573
            return;
×
574
        }
575

576
        // Filter out QGroundControl messages similar to regular mavlink processing
577
        if (_configuration.get_component_type() == ComponentType::GroundStation &&
2,480✔
578
            message.system_id == 255 && message.component_id == MAV_COMP_ID_MISSIONPLANNER) {
2,479✔
579
            if (_message_logging_on) {
×
580
                LogDebug() << "Ignoring libmav messages from QGC as we are also a ground station";
×
581
            }
582
            return;
×
583
        }
584

585
        bool found_system = false;
2,479✔
586
        for (auto& system : _systems) {
2,510✔
587
            if (system.first == message.system_id) {
2,506✔
588
                system.second->system_impl()->add_new_component(message.component_id);
2,475✔
589
                found_system = true;
2,474✔
590
                break;
2,474✔
591
            }
592
        }
593

594
        if (!found_system) {
2,481✔
595
            if (_system_debugging) {
7✔
596
                LogWarn() << "Create new system/component from libmav " << (int)message.system_id
×
597
                          << "/" << (int)message.component_id;
×
598
            }
599
            make_system_with_component(message.system_id, message.component_id);
7✔
600

601
            // We now better talk back.
602
            start_sending_heartbeats();
7✔
603
        }
604

605
        if (_should_exit) {
2,481✔
606
            // Don't try to call at() if systems have already been destroyed
607
            // in destructor.
608
            return;
×
609
        }
610
    }
2,479✔
611

612
    // Distribute libmav message to systems for libmav-specific handling
613
    bool found_system = false;
2,482✔
614
    for (auto& system : _systems) {
5,030✔
615
        if (system.first == message.system_id) {
2,541✔
616
            if (_message_logging_on) {
2,475✔
617
                LogDebug() << "Distributing libmav message " << message.message_name
×
618
                           << " to SystemImpl for system " << system.first;
×
619
            }
620
            system.second->system_impl()->process_libmav_message(message);
2,475✔
621
            found_system = true;
2,482✔
622
            // Don't break - distribute to all matching system instances
623
        }
624
    }
625

626
    if (!found_system) {
2,481✔
627
        LogWarn() << "No system found for libmav message " << message.message_name
×
628
                  << " from system " << message.system_id;
×
629
    }
630
}
631

632
bool MavsdkImpl::send_message(mavlink_message_t& message)
2,630✔
633
{
634
    // Create a copy of the message to avoid reference issues
635
    mavlink_message_t message_copy = message;
2,630✔
636

637
    {
638
        std::lock_guard lock(_messages_to_send_mutex);
2,630✔
639
        _messages_to_send.push(std::move(message_copy));
2,639✔
640
    }
2,637✔
641

642
    // For heartbeat messages, we want to process them immediately to speed up system discovery
643
    if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
2,639✔
644
        // Trigger message processing in the work thread
645
        // This is a hint to process messages sooner, but doesn't block
646
        std::this_thread::yield();
442✔
647
    }
648

649
    return true;
2,639✔
650
}
651

652
void MavsdkImpl::deliver_messages()
33,909✔
653
{
654
    // Process messages one at a time to avoid holding the mutex while delivering
655
    while (true) {
656
        mavlink_message_t message;
657
        {
658
            std::lock_guard lock(_messages_to_send_mutex);
33,909✔
659
            if (_messages_to_send.empty()) {
34,941✔
660
                break;
31,483✔
661
            }
662
            message = _messages_to_send.front();
2,637✔
663
            _messages_to_send.pop();
2,637✔
664
        }
34,120✔
665
        deliver_message(message);
2,640✔
666
    }
2,640✔
667
}
32,243✔
668

669
void MavsdkImpl::deliver_message(mavlink_message_t& message)
2,635✔
670
{
671
    if (_message_logging_on) {
2,635✔
672
        LogDebug() << "Sending message " << message.msgid << " from "
×
673
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid)
×
674
                   << " to " << static_cast<int>(get_target_system_id(message)) << "/"
×
675
                   << static_cast<int>(get_target_component_id(message));
×
676
    }
677

678
    // This is a low level interface where outgoing messages can be tampered
679
    // with or even dropped.
680
    bool keep = true;
2,635✔
681
    {
682
        std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
2,635✔
683
        if (_intercept_outgoing_messages_callback != nullptr) {
2,640✔
684
            keep = _intercept_outgoing_messages_callback(message);
229✔
685
        }
686
    }
2,640✔
687

688
    if (!keep) {
2,641✔
689
        // We fake that everything was sent as instructed because
690
        // a potential loss would happen later, and we would not be informed
691
        // about it.
692
        LogDebug() << "Dropped outgoing message: " << int(message.msgid);
88✔
693
        return;
175✔
694
    }
695

696
    // JSON message interception for outgoing messages
697
    // Convert mavlink_message_t to Mavsdk::MavlinkMessage for JSON interception
698
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
699
    uint16_t len = mavlink_msg_to_send_buffer(buffer, &message);
2,553✔
700

701
    size_t bytes_consumed = 0;
2,550✔
702
    auto libmav_msg_opt = parse_message_safe(buffer, len, bytes_consumed);
2,550✔
703

704
    if (libmav_msg_opt) {
2,549✔
705
        // Create Mavsdk::MavlinkMessage directly for JSON interception
706
        Mavsdk::MavlinkMessage json_message;
2,552✔
707
        json_message.message_name = libmav_msg_opt.value().name();
2,547✔
708
        json_message.system_id = message.sysid;
2,544✔
709
        json_message.component_id = message.compid;
2,544✔
710

711
        // Extract target_system and target_component if present
712
        uint8_t target_system_id = 0;
2,544✔
713
        uint8_t target_component_id = 0;
2,544✔
714
        if (libmav_msg_opt.value().get("target_system", target_system_id) ==
2,544✔
715
            mav::MessageResult::Success) {
716
            json_message.target_system_id = target_system_id;
1,865✔
717
        } else {
718
            json_message.target_system_id = 0;
681✔
719
        }
720
        if (libmav_msg_opt.value().get("target_component", target_component_id) ==
2,546✔
721
            mav::MessageResult::Success) {
722
            json_message.target_component_id = target_component_id;
1,866✔
723
        } else {
724
            json_message.target_component_id = 0;
686✔
725
        }
726

727
        // Generate JSON using LibmavReceiver's public method
728
        auto connections = get_connections();
2,552✔
729
        if (!connections.empty() && connections[0]->get_libmav_receiver()) {
2,552✔
730
            json_message.fields_json =
731
                connections[0]->get_libmav_receiver()->libmav_message_to_json(
7,382✔
732
                    libmav_msg_opt.value());
4,921✔
733
        } else {
734
            // Fallback: create minimal JSON if no receiver available
735
            json_message.fields_json =
736
                "{\"message_id\":" + std::to_string(libmav_msg_opt.value().id()) +
174✔
737
                ",\"message_name\":\"" + libmav_msg_opt.value().name() + "\"}";
174✔
738
        }
739

740
        if (!call_json_interception_callbacks(json_message, _outgoing_json_message_subscriptions)) {
2,546✔
741
            // Message was dropped by JSON interception callback
742
            if (_message_logging_on) {
×
743
                LogDebug() << "Outgoing JSON message " << json_message.message_name
×
744
                           << " dropped by interception";
×
745
            }
746
            return;
×
747
        }
748
    }
2,543✔
749

750
    std::lock_guard lock(_mutex);
2,548✔
751

752
    if (_connections.empty()) {
2,553✔
753
        // We obviously can't send any messages without a connection added, so
754
        // we silently ignore this.
755
        return;
87✔
756
    }
757

758
    uint8_t successful_emissions = 0;
2,461✔
759
    for (auto& _connection : _connections) {
4,945✔
760
        const uint8_t target_system_id = get_target_system_id(message);
2,476✔
761

762
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
2,482✔
763
            continue;
5✔
764
        }
765
        const auto result = (*_connection.connection).send_message(message);
2,469✔
766
        if (result.first) {
2,479✔
767
            successful_emissions++;
2,473✔
768
        } else {
769
            _connections_errors_subscriptions.queue(
12✔
770
                Mavsdk::ConnectionError{result.second, _connection.handle},
6✔
771
                [this](const auto& func) { call_user_callback(func); });
×
772
        }
773
    }
2,479✔
774

775
    if (successful_emissions == 0) {
2,466✔
776
        LogErr() << "Sending message failed";
4✔
777
    }
778
}
2,553✔
779

780
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
144✔
781
    const std::string& connection_url, ForwardingOption forwarding_option)
782
{
783
    CliArg cli_arg;
144✔
784
    if (!cli_arg.parse(connection_url)) {
144✔
785
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
786
    }
787

788
    return std::visit(
144✔
789
        overloaded{
288✔
790
            [](std::monostate) {
×
791
                // Should not happen anyway.
792
                return std::pair<ConnectionResult, Mavsdk::ConnectionHandle>{
×
793
                    ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle()};
×
794
            },
795
            [this, forwarding_option](const CliArg::Udp& udp) {
134✔
796
                return add_udp_connection(udp, forwarding_option);
134✔
797
            },
798
            [this, forwarding_option](const CliArg::Tcp& tcp) {
8✔
799
                return add_tcp_connection(tcp, forwarding_option);
8✔
800
            },
801
            [this, forwarding_option](const CliArg::Serial& serial) {
×
802
                return add_serial_connection(
×
803
                    serial.path, serial.baudrate, serial.flow_control_enabled, forwarding_option);
×
804
            },
805
            [this, forwarding_option](const CliArg::Raw&) {
2✔
806
                return add_raw_connection(forwarding_option);
2✔
807
            }},
808
        cli_arg.protocol);
144✔
809
}
144✔
810

811
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
812
MavsdkImpl::add_udp_connection(const CliArg::Udp& udp, ForwardingOption forwarding_option)
134✔
813
{
814
    auto new_conn = std::make_unique<UdpConnection>(
815
        [this](
2,425✔
816
            MavlinkReceiver::ParseResult result,
817
            mavlink_message_t& message,
818
            Connection* connection) { receive_message(result, message, connection); },
2,425✔
819
        [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
2,428✔
820
            receive_libmav_message(message, connection);
2,428✔
821
        },
2,430✔
822
        *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
823
        udp.mode == CliArg::Udp::Mode::In ? udp.host : "0.0.0.0",
268✔
824
        udp.mode == CliArg::Udp::Mode::In ? udp.port : 0,
134✔
825
        forwarding_option);
134✔
826

827
    if (!new_conn) {
134✔
828
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
829
    }
830

831
    ConnectionResult ret = new_conn->start();
134✔
832

833
    if (ret != ConnectionResult::Success) {
134✔
834
        return {ret, Mavsdk::ConnectionHandle{}};
×
835
    }
836

837
    if (udp.mode == CliArg::Udp::Mode::Out) {
134✔
838
        // We need to add the IP rather than a hostname, otherwise we end up with two remotes:
839
        // one for the IP, and one for a hostname.
840
        auto remote_ip = resolve_hostname_to_ip(udp.host);
67✔
841

842
        if (!remote_ip) {
67✔
843
            return {ConnectionResult::DestinationIpUnknown, Mavsdk::ConnectionHandle{}};
×
844
        }
845

846
        new_conn->add_remote_to_keep(remote_ip.value(), udp.port);
67✔
847
        std::lock_guard lock(_mutex);
67✔
848

849
        // With a UDP remote, we need to initiate the connection by sending heartbeats.
850
        auto new_configuration = get_configuration();
67✔
851
        new_configuration.set_always_send_heartbeats(true);
67✔
852
        set_configuration(new_configuration);
67✔
853
    }
67✔
854

855
    auto handle = add_connection(std::move(new_conn));
134✔
856

857
    return {ConnectionResult::Success, handle};
134✔
858
}
134✔
859

860
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
861
MavsdkImpl::add_tcp_connection(const CliArg::Tcp& tcp, ForwardingOption forwarding_option)
8✔
862
{
863
    if (tcp.mode == CliArg::Tcp::Mode::Out) {
8✔
864
        auto new_conn = std::make_unique<TcpClientConnection>(
865
            [this](
36✔
866
                MavlinkReceiver::ParseResult result,
867
                mavlink_message_t& message,
868
                Connection* connection) { receive_message(result, message, connection); },
36✔
869
            [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
36✔
870
                receive_libmav_message(message, connection);
36✔
871
            },
36✔
872
            *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
873
            tcp.host,
4✔
874
            tcp.port,
4✔
875
            forwarding_option);
4✔
876
        if (!new_conn) {
4✔
877
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
878
        }
879
        ConnectionResult ret = new_conn->start();
4✔
880
        if (ret == ConnectionResult::Success) {
4✔
881
            return {ret, add_connection(std::move(new_conn))};
4✔
882
        } else {
883
            return {ret, Mavsdk::ConnectionHandle{}};
×
884
        }
885
    } else {
4✔
886
        auto new_conn = std::make_unique<TcpServerConnection>(
887
            [this](
31✔
888
                MavlinkReceiver::ParseResult result,
889
                mavlink_message_t& message,
890
                Connection* connection) { receive_message(result, message, connection); },
31✔
891
            [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
31✔
892
                receive_libmav_message(message, connection);
31✔
893
            },
31✔
894
            *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
895
            tcp.host,
4✔
896
            tcp.port,
4✔
897
            forwarding_option);
4✔
898
        if (!new_conn) {
4✔
899
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
900
        }
901
        ConnectionResult ret = new_conn->start();
4✔
902
        if (ret == ConnectionResult::Success) {
4✔
903
            return {ret, add_connection(std::move(new_conn))};
4✔
904
        } else {
905
            return {ret, Mavsdk::ConnectionHandle{}};
×
906
        }
907
    }
4✔
908
}
909

910
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
911
    const std::string& dev_path,
912
    int baudrate,
913
    bool flow_control,
914
    ForwardingOption forwarding_option)
915
{
916
    auto new_conn = std::make_unique<SerialConnection>(
917
        [this](
×
918
            MavlinkReceiver::ParseResult result,
919
            mavlink_message_t& message,
920
            Connection* connection) { receive_message(result, message, connection); },
×
921
        [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
×
922
            receive_libmav_message(message, connection);
×
923
        },
×
924
        *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
925
        dev_path,
926
        baudrate,
927
        flow_control,
928
        forwarding_option);
×
929
    if (!new_conn) {
×
930
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
931
    }
932
    ConnectionResult ret = new_conn->start();
×
933
    if (ret == ConnectionResult::Success) {
×
934
        auto handle = add_connection(std::move(new_conn));
×
935

936
        auto new_configuration = get_configuration();
×
937

938
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
939
        // to initiate the MAVLink connection by sending heartbeats.
940
        // Therefore, we override the default here and enable sending heartbeats.
941
        new_configuration.set_always_send_heartbeats(true);
×
942
        set_configuration(new_configuration);
×
943

944
        return {ret, handle};
×
945

946
    } else {
947
        return {ret, Mavsdk::ConnectionHandle{}};
×
948
    }
949
}
×
950

951
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
952
MavsdkImpl::add_raw_connection(ForwardingOption forwarding_option)
2✔
953
{
954
    // Check if a raw connection already exists
955
    if (find_raw_connection() != nullptr) {
2✔
956
        LogErr() << "Raw connection already exists. Only one raw connection is allowed.";
×
957
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
958
    }
959

960
    auto new_conn = std::make_unique<RawConnection>(
961
        [this](
1✔
962
            MavlinkReceiver::ParseResult result,
963
            mavlink_message_t& message,
964
            Connection* connection) { receive_message(result, message, connection); },
1✔
965
        [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
1✔
966
            receive_libmav_message(message, connection);
1✔
967
        },
1✔
968
        *this,
969
        forwarding_option);
2✔
970

971
    if (!new_conn) {
2✔
972
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
973
    }
974

975
    ConnectionResult ret = new_conn->start();
2✔
976
    if (ret != ConnectionResult::Success) {
2✔
977
        return {ret, Mavsdk::ConnectionHandle{}};
×
978
    }
979

980
    auto handle = add_connection(std::move(new_conn));
2✔
981

982
    // Enable heartbeats for raw connection
983
    auto new_configuration = get_configuration();
2✔
984
    new_configuration.set_always_send_heartbeats(true);
2✔
985
    set_configuration(new_configuration);
2✔
986

987
    return {ConnectionResult::Success, handle};
2✔
988
}
2✔
989

990
Mavsdk::ConnectionHandle MavsdkImpl::add_connection(std::unique_ptr<Connection>&& new_connection)
144✔
991
{
992
    std::lock_guard lock(_mutex);
144✔
993
    auto handle = _connections_handle_factory.create();
144✔
994
    _connections.emplace_back(ConnectionEntry{std::move(new_connection), handle});
144✔
995

996
    return handle;
288✔
997
}
144✔
998

999
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
12✔
1000
{
1001
    std::lock_guard lock(_mutex);
12✔
1002

1003
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
12✔
1004
        return (entry.handle == handle);
12✔
1005
    }));
1006
}
12✔
1007

1008
Mavsdk::Configuration MavsdkImpl::get_configuration() const
69✔
1009
{
1010
    std::lock_guard configuration_lock(_mutex);
69✔
1011
    return _configuration;
138✔
1012
}
69✔
1013

1014
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
207✔
1015
{
1016
    std::lock_guard server_components_lock(_server_components_mutex);
207✔
1017
    // We just point the default to the newly created component. This means
1018
    // that the previous default component will be deleted if it is not
1019
    // used/referenced anywhere.
1020
    _default_server_component =
1021
        server_component_by_id_with_lock(new_configuration.get_component_id());
207✔
1022

1023
    if (new_configuration.get_always_send_heartbeats() &&
345✔
1024
        !_configuration.get_always_send_heartbeats()) {
138✔
1025
        start_sending_heartbeats();
73✔
1026
    } else if (
134✔
1027
        !new_configuration.get_always_send_heartbeats() &&
203✔
1028
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
203✔
1029
        stop_sending_heartbeats();
×
1030
    }
1031

1032
    _configuration = new_configuration;
207✔
1033
    // We cache these values as atomic to avoid having to lock any mutex for them.
1034
    _our_system_id = new_configuration.get_system_id();
207✔
1035
    _our_component_id = new_configuration.get_component_id();
207✔
1036
}
207✔
1037

1038
uint8_t MavsdkImpl::get_own_system_id() const
5,906✔
1039
{
1040
    return _our_system_id;
5,906✔
1041
}
1042

1043
uint8_t MavsdkImpl::get_own_component_id() const
1,465✔
1044
{
1045
    return _our_component_id;
1,465✔
1046
}
1047

1048
uint8_t MavsdkImpl::channel() const
×
1049
{
1050
    // TODO
1051
    return 0;
×
1052
}
1053

1054
Autopilot MavsdkImpl::autopilot() const
×
1055
{
1056
    // TODO
1057
    return Autopilot::Px4;
×
1058
}
1059

1060
// FIXME: this should be per component
1061
uint8_t MavsdkImpl::get_mav_type() const
428✔
1062
{
1063
    return _configuration.get_mav_type();
428✔
1064
}
1065

1066
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
142✔
1067
{
1068
    // Needs _systems_lock
1069

1070
    if (_should_exit) {
142✔
1071
        // When the system got destroyed in the destructor, we have to give up.
1072
        return;
×
1073
    }
1074

1075
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
142✔
1076
        LogDebug() << "Initializing connection to remote system...";
×
1077
    } else {
1078
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
284✔
1079
                   << " Comp ID: " << static_cast<int>(comp_id);
142✔
1080
    }
1081

1082
    // Make a system with its first component
1083
    auto new_system = std::make_shared<System>(*this);
142✔
1084
    new_system->init(system_id, comp_id);
142✔
1085

1086
    _systems.emplace_back(system_id, new_system);
142✔
1087
}
142✔
1088

1089
void MavsdkImpl::notify_on_discover()
145✔
1090
{
1091
    // Queue the callbacks without holding the mutex to avoid deadlocks
1092
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
210✔
1093
}
145✔
1094

1095
void MavsdkImpl::notify_on_timeout()
5✔
1096
{
1097
    // Queue the callbacks without holding the mutex to avoid deadlocks
1098
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
5✔
1099
}
5✔
1100

1101
Mavsdk::NewSystemHandle
1102
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
64✔
1103
{
1104
    std::lock_guard lock(_mutex);
64✔
1105

1106
    const auto handle = _new_system_callbacks.subscribe(callback);
64✔
1107

1108
    if (is_any_system_connected()) {
64✔
1109
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
1110
    }
1111

1112
    return handle;
128✔
1113
}
64✔
1114

1115
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
63✔
1116
{
1117
    _new_system_callbacks.unsubscribe(handle);
63✔
1118
}
63✔
1119

1120
bool MavsdkImpl::is_any_system_connected() const
64✔
1121
{
1122
    std::vector<std::shared_ptr<System>> connected_systems = systems();
64✔
1123
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
64✔
1124
        return system->is_connected();
×
1125
    });
64✔
1126
}
64✔
1127

1128
void MavsdkImpl::work_thread()
138✔
1129
{
1130
    while (!_should_exit) {
32,379✔
1131
        // Process incoming messages
1132
        process_messages();
32,184✔
1133

1134
        // Process incoming libmav messages
1135
        process_libmav_messages();
31,627✔
1136

1137
        // Run timers
1138
        timeout_handler.run_once();
32,278✔
1139
        call_every_handler.run_once();
31,539✔
1140

1141
        // Do component work
1142
        {
1143
            std::lock_guard lock(_server_components_mutex);
32,098✔
1144
            for (auto& it : _server_components) {
64,072✔
1145
                if (it.second != nullptr) {
31,977✔
1146
                    it.second->_impl->do_work();
32,186✔
1147
                }
1148
            }
1149
        }
32,168✔
1150

1151
        // Deliver outgoing messages
1152
        deliver_messages();
32,278✔
1153

1154
        // If no messages to send, check if there are messages to receive
1155
        std::unique_lock lock_received(_received_messages_mutex);
32,049✔
1156
        if (_received_messages.empty()) {
32,276✔
1157
            // No messages to process, wait for a signal or timeout
1158
            _received_messages_cv.wait_for(lock_received, std::chrono::milliseconds(10), [this]() {
31,989✔
1159
                return !_received_messages.empty() || _should_exit;
62,499✔
1160
            });
1161
        }
1162
    }
31,103✔
1163
}
243✔
1164

1165
void MavsdkImpl::call_user_callback_located(
1,228✔
1166
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1167
{
1168
    // Don't enqueue callbacks if we're shutting down
1169
    if (_should_exit) {
1,228✔
1170
        return;
×
1171
    }
1172

1173
    auto callback_size = _user_callback_queue.size();
1,228✔
1174

1175
    if (_callback_tracker) {
1,228✔
1176
        _callback_tracker->record_queued(filename, linenumber);
×
1177
        _callback_tracker->maybe_print_stats(callback_size);
×
1178
    }
1179

1180
    if (callback_size >= 100) {
1,228✔
1181
        return;
×
1182

1183
    } else if (callback_size == 99) {
1,228✔
1184
        LogErr()
×
1185
            << "User callback queue overflown\n"
1186
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1187
        return;
×
1188

1189
    } else if (callback_size >= 10) {
1,228✔
1190
        LogWarn()
×
1191
            << "User callback queue slow (queue size: " << callback_size
×
1192
            << ").\n"
1193
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1194
    }
1195

1196
    // We only need to keep track of filename and linenumber if we're actually debugging this.
1197
    UserCallback user_callback =
1198
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
2,456✔
1199

1200
    _user_callback_queue.push_back(std::make_shared<UserCallback>(user_callback));
1,228✔
1201
}
1,228✔
1202

1203
void MavsdkImpl::process_user_callbacks_thread()
138✔
1204
{
1205
    while (!_should_exit) {
1,504✔
1206
        UserCallback callback;
1,365✔
1207
        {
1208
            LockedQueue<UserCallback>::Guard guard(_user_callback_queue);
1,365✔
1209
            auto ptr = guard.wait_and_pop_front();
1,366✔
1210
            if (!ptr) {
1,366✔
1211
                continue;
138✔
1212
            }
1213
            // We need to get a copy instead of just a shared_ptr because the queue might
1214
            // be invalidated when the lock is released.
1215
            callback = *ptr;
1,228✔
1216
        }
1,504✔
1217

1218
        // Check if we're in the process of shutting down before executing the callback
1219
        if (_should_exit) {
1,228✔
1220
            continue;
×
1221
        }
1222

1223
        const double timeout_s = 1.0;
1,228✔
1224
        auto cookie = timeout_handler.add(
1,228✔
1225
            [&]() {
×
1226
                if (_callback_debugging) {
×
1227
                    LogWarn() << "Callback called from " << callback.filename << ":"
×
1228
                              << callback.linenumber << " took more than " << timeout_s
×
1229
                              << " second to run.";
×
1230
                    fflush(stdout);
×
1231
                    fflush(stderr);
×
1232
                    abort();
×
1233
                } else {
1234
                    LogWarn()
×
1235
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
1236
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1237
                }
1238
            },
×
1239
            timeout_s);
1240
        auto callback_start = std::chrono::steady_clock::now();
1,227✔
1241
        callback.func();
1,227✔
1242
        auto callback_end = std::chrono::steady_clock::now();
1,228✔
1243
        timeout_handler.remove(cookie);
1,228✔
1244

1245
        if (_callback_tracker) {
1,228✔
1246
            auto callback_duration_us =
1247
                std::chrono::duration_cast<std::chrono::microseconds>(callback_end - callback_start)
×
1248
                    .count();
×
1249
            _callback_tracker->record_executed(
×
1250
                callback.filename, callback.linenumber, callback_duration_us);
1251
        }
1252
    }
1,365✔
1253
}
138✔
1254

1255
void MavsdkImpl::start_sending_heartbeats()
360✔
1256
{
1257
    // Check if we're in the process of shutting down
1258
    if (_should_exit) {
360✔
1259
        return;
×
1260
    }
1261

1262
    // Before sending out first heartbeats we need to make sure we have a
1263
    // default server component.
1264
    default_server_component_impl();
360✔
1265

1266
    {
1267
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
361✔
1268
        call_every_handler.remove(_heartbeat_send_cookie);
361✔
1269
        _heartbeat_send_cookie =
361✔
1270
            call_every_handler.add([this]() { send_heartbeats(); }, HEARTBEAT_SEND_INTERVAL_S);
789✔
1271
    }
361✔
1272
}
1273

1274
void MavsdkImpl::stop_sending_heartbeats()
5✔
1275
{
1276
    if (!_configuration.get_always_send_heartbeats()) {
5✔
1277
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
1✔
1278
        call_every_handler.remove(_heartbeat_send_cookie);
1✔
1279
    }
1✔
1280
}
5✔
1281

1282
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
1,391✔
1283
{
1284
    std::lock_guard lock(_server_components_mutex);
1,391✔
1285
    return default_server_component_with_lock();
1,393✔
1286
}
1,393✔
1287

1288
ServerComponentImpl& MavsdkImpl::default_server_component_with_lock()
1,391✔
1289
{
1290
    if (_default_server_component == nullptr) {
1,391✔
1291
        _default_server_component = server_component_by_id_with_lock(_our_component_id);
×
1292
    }
1293
    return *_default_server_component->_impl;
1,392✔
1294
}
1295

1296
void MavsdkImpl::send_heartbeats()
428✔
1297
{
1298
    std::lock_guard lock(_server_components_mutex);
428✔
1299

1300
    for (auto& it : _server_components) {
864✔
1301
        if (it.second != nullptr) {
429✔
1302
            it.second->_impl->send_heartbeat();
432✔
1303
        }
1304
    }
1305
}
439✔
1306

1307
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
24✔
1308
{
1309
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
24✔
1310
    _intercept_incoming_messages_callback = callback;
24✔
1311
}
24✔
1312

1313
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
1314
{
1315
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
14✔
1316
    _intercept_outgoing_messages_callback = callback;
14✔
1317
}
14✔
1318

1319
bool MavsdkImpl::call_json_interception_callbacks(
5,022✔
1320
    const Mavsdk::MavlinkMessage& json_message,
1321
    std::vector<std::pair<Mavsdk::InterceptJsonHandle, Mavsdk::InterceptJsonCallback>>&
1322
        callback_list)
1323
{
1324
    bool keep_message = true;
5,022✔
1325

1326
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
5,022✔
1327
    for (const auto& subscription : callback_list) {
5,037✔
1328
        if (!subscription.second(json_message)) {
2✔
1329
            keep_message = false;
×
1330
        }
1331
    }
1332

1333
    return keep_message;
10,057✔
1334
}
5,027✔
1335

1336
Mavsdk::InterceptJsonHandle
1337
MavsdkImpl::subscribe_incoming_messages_json(const Mavsdk::InterceptJsonCallback& callback)
1✔
1338
{
1339
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1340
    auto handle = _json_handle_factory.create();
1✔
1341
    _incoming_json_message_subscriptions.push_back(std::make_pair(handle, callback));
1✔
1342
    return handle;
2✔
1343
}
1✔
1344

1345
void MavsdkImpl::unsubscribe_incoming_messages_json(Mavsdk::InterceptJsonHandle handle)
1✔
1346
{
1347
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1348
    auto it = std::find_if(
1✔
1349
        _incoming_json_message_subscriptions.begin(),
1350
        _incoming_json_message_subscriptions.end(),
1351
        [handle](const auto& subscription) { return subscription.first == handle; });
1✔
1352
    if (it != _incoming_json_message_subscriptions.end()) {
1✔
1353
        _incoming_json_message_subscriptions.erase(it);
1✔
1354
    }
1355
}
1✔
1356

1357
Mavsdk::InterceptJsonHandle
1358
MavsdkImpl::subscribe_outgoing_messages_json(const Mavsdk::InterceptJsonCallback& callback)
1✔
1359
{
1360
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1361
    auto handle = _json_handle_factory.create();
1✔
1362
    _outgoing_json_message_subscriptions.push_back(std::make_pair(handle, callback));
1✔
1363
    return handle;
2✔
1364
}
1✔
1365

1366
void MavsdkImpl::unsubscribe_outgoing_messages_json(Mavsdk::InterceptJsonHandle handle)
1✔
1367
{
1368
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1369
    auto it = std::find_if(
1✔
1370
        _outgoing_json_message_subscriptions.begin(),
1371
        _outgoing_json_message_subscriptions.end(),
1372
        [handle](const auto& subscription) { return subscription.first == handle; });
1✔
1373
    if (it != _outgoing_json_message_subscriptions.end()) {
1✔
1374
        _outgoing_json_message_subscriptions.erase(it);
1✔
1375
    }
1376
}
1✔
1377

1378
RawConnection* MavsdkImpl::find_raw_connection()
4✔
1379
{
1380
    std::lock_guard lock(_mutex);
4✔
1381

1382
    for (auto& entry : _connections) {
4✔
1383
        auto* raw_conn = dynamic_cast<RawConnection*>(entry.connection.get());
2✔
1384
        if (raw_conn != nullptr) {
2✔
1385
            return raw_conn;
2✔
1386
        }
1387
    }
1388
    return nullptr;
2✔
1389
}
4✔
1390

1391
void MavsdkImpl::pass_received_raw_bytes(const char* bytes, size_t length)
1✔
1392
{
1393
    auto* raw_conn = find_raw_connection();
1✔
1394
    if (raw_conn == nullptr) {
1✔
1395
        LogErr()
×
1396
            << "No raw connection available. Please add one using add_any_connection(\"raw://\")";
×
1397
        return;
×
1398
    }
1399

1400
    raw_conn->receive(bytes, length);
1✔
1401
}
1402

1403
Mavsdk::RawBytesHandle
1404
MavsdkImpl::subscribe_raw_bytes_to_be_sent(const Mavsdk::RawBytesCallback& callback)
1✔
1405
{
1406
    if (find_raw_connection() == nullptr) {
1✔
1407
        LogWarn() << "No raw connection available. Subscription will only receive bytes after you "
×
1408
                     "add a connection using add_any_connection(\"raw://\")";
×
1409
    }
1410
    return _raw_bytes_subscriptions.subscribe(callback);
1✔
1411
}
1412

1413
void MavsdkImpl::unsubscribe_raw_bytes_to_be_sent(Mavsdk::RawBytesHandle handle)
1✔
1414
{
1415
    _raw_bytes_subscriptions.unsubscribe(handle);
1✔
1416
}
1✔
1417

1418
bool MavsdkImpl::notify_raw_bytes_sent(const char* bytes, size_t length)
3✔
1419
{
1420
    if (_raw_bytes_subscriptions.empty()) {
3✔
1421
        return false;
2✔
1422
    }
1423

1424
    _raw_bytes_subscriptions(bytes, length);
1✔
1425

1426
    return true;
1✔
1427
}
1428

1429
Mavsdk::ConnectionErrorHandle
1430
MavsdkImpl::subscribe_connection_errors(Mavsdk::ConnectionErrorCallback callback)
×
1431
{
1432
    std::lock_guard lock(_mutex);
×
1433

1434
    const auto handle = _connections_errors_subscriptions.subscribe(callback);
×
1435

1436
    return handle;
×
1437
}
×
1438

1439
void MavsdkImpl::unsubscribe_connection_errors(Mavsdk::ConnectionErrorHandle handle)
×
1440
{
1441
    std::lock_guard lock(_mutex);
×
1442
    _connections_errors_subscriptions.unsubscribe(handle);
×
1443
}
×
1444

1445
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
2,521✔
1446
{
1447
    // Checks whether connection knows target system ID by extracting target system if set.
1448
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
2,521✔
1449

1450
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
2,528✔
1451
        return 0;
643✔
1452
    }
1453

1454
    // Don't look at the target system offset if it is outside the payload length.
1455
    // This can happen if the fields are trimmed.
1456
    if (meta->target_system_ofs >= message.len) {
1,885✔
1457
        return 0;
22✔
1458
    }
1459

1460
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,863✔
1461
}
1462

1463
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
47✔
1464
{
1465
    // Checks whether connection knows target system ID by extracting target system if set.
1466
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
47✔
1467

1468
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
47✔
1469
        return 0;
32✔
1470
    }
1471

1472
    // Don't look at the target component offset if it is outside the payload length.
1473
    // This can happen if the fields are trimmed.
1474
    if (meta->target_component_ofs >= message.len) {
15✔
1475
        return 0;
1✔
1476
    }
1477

1478
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
14✔
1479
}
1480

1481
Sender& MavsdkImpl::sender()
×
1482
{
1483
    std::lock_guard lock(_server_components_mutex);
×
1484
    return default_server_component_with_lock().sender();
×
1485
}
×
1486

1487
std::vector<Connection*> MavsdkImpl::get_connections() const
2,545✔
1488
{
1489
    std::lock_guard lock(_mutex);
2,545✔
1490
    std::vector<Connection*> connections;
2,553✔
1491
    for (const auto& connection_entry : _connections) {
5,021✔
1492
        connections.push_back(connection_entry.connection.get());
2,475✔
1493
    }
1494
    return connections;
2,552✔
1495
}
2,552✔
1496

1497
mav::MessageSet& MavsdkImpl::get_message_set() const
23✔
1498
{
1499
    // Note: This returns a reference to MessageSet without locking.
1500
    // Thread safety for MessageSet operations must be ensured by:
1501
    // 1. Using load_custom_xml_to_message_set() for write operations (XML loading)
1502
    // 2. libmav MessageSet should be internally thread-safe for read operations
1503
    // 3. If race conditions persist, consider implementing a thread-safe MessageSet wrapper
1504
    return *_message_set;
23✔
1505
}
1506

1507
bool MavsdkImpl::load_custom_xml_to_message_set(const std::string& xml_content)
6✔
1508
{
1509
    std::lock_guard<std::mutex> lock(_message_set_mutex);
6✔
1510
    auto result = _message_set->addFromXMLString(xml_content, false /* recursive_open_includes */);
6✔
1511
    return result == ::mav::MessageSetResult::Success;
12✔
1512
}
6✔
1513

1514
// Thread-safe MessageSet read operations
1515
std::optional<std::string> MavsdkImpl::message_id_to_name_safe(uint32_t id) const
×
1516
{
1517
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1518
    auto message_def = _message_set->getMessageDefinition(static_cast<int>(id));
×
1519
    if (message_def) {
×
1520
        return message_def.get().name();
×
1521
    }
1522
    return std::nullopt;
×
1523
}
×
1524

1525
std::optional<int> MavsdkImpl::message_name_to_id_safe(const std::string& name) const
×
1526
{
1527
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1528
    return _message_set->idForMessage(name);
×
1529
}
×
1530

1531
std::optional<mav::Message> MavsdkImpl::create_message_safe(const std::string& message_name) const
×
1532
{
1533
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1534
    return _message_set->create(message_name);
×
1535
}
×
1536

1537
// Thread-safe parsing for LibmavReceiver
1538
std::optional<mav::Message> MavsdkImpl::parse_message_safe(
5,036✔
1539
    const uint8_t* buffer, size_t buffer_len, size_t& bytes_consumed) const
1540
{
1541
    std::lock_guard<std::mutex> lock(_message_set_mutex);
5,036✔
1542
    return _buffer_parser->parseMessage(buffer, buffer_len, bytes_consumed);
5,052✔
1543
}
5,037✔
1544

1545
mav::OptionalReference<const mav::MessageDefinition>
1546
MavsdkImpl::get_message_definition_safe(int message_id) const
4,956✔
1547
{
1548
    std::lock_guard<std::mutex> lock(_message_set_mutex);
4,956✔
1549
    return _message_set->getMessageDefinition(message_id);
4,964✔
1550
}
4,961✔
1551

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