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

mavlink / MAVSDK / 18812329569

26 Oct 2025 03:26AM UTC coverage: 48.169% (-0.08%) from 48.247%
18812329569

Pull #2694

github

web-flow
Merge 0de7714b2 into 5b66d5fb8
Pull Request #2694: User callback debugging and MavlinkDirect improvements

12 of 79 new or added lines in 4 files covered. (15.19%)

11 existing lines in 7 files now uncovered.

17432 of 36189 relevant lines covered (48.17%)

470.65 hits per line

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

71.65
/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 "system.h"
13
#include "system_impl.h"
14
#include "serial_connection.h"
15
#include "version.h"
16
#include "server_component_impl.h"
17
#include "overloaded.h"
18
#include "mavlink_channels.h"
19
#include "callback_list.tpp"
20
#include "hostname_to_ip.h"
21
#include "embedded_mavlink_xml.h"
22
#include <mav/MessageSet.h>
23

24
namespace mavsdk {
25

26
template class CallbackList<>;
27

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

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

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

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

56
    set_configuration(configuration);
132✔
57

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

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

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

72
    _process_user_callbacks_thread =
264✔
73
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
132✔
74

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

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

85
    _should_exit = true;
132✔
86

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

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

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

103
    std::lock_guard lock(_mutex);
132✔
104

105
    _systems.clear();
132✔
106
    _connections.clear();
132✔
107
}
132✔
108

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

113
    ++version_counter;
1✔
114

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

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

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

152
    return systems_result;
170✔
153
}
170✔
154

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

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

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

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

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

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

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

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

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

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

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

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

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

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

288
    std::lock_guard lock(_server_components_mutex);
51✔
289

290
    return server_component_by_id_with_lock(component_id);
51✔
291
}
51✔
292

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

305
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
133✔
306
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
266✔
307

308
    return _server_components.back().second;
133✔
309
}
310

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

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

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

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

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

352
void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connection)
2,456✔
353
{
354
    {
355
        std::lock_guard lock(_received_messages_mutex);
2,456✔
356
        _received_messages.emplace(ReceivedMessage{std::move(message), connection});
2,461✔
357
    }
2,459✔
358
    _received_messages_cv.notify_one();
2,458✔
359
}
2,461✔
360

361
void MavsdkImpl::receive_libmav_message(
2,456✔
362
    const Mavsdk::MavlinkMessage& message, Connection* connection)
363
{
364
    {
365
        std::lock_guard lock(_received_libmav_messages_mutex);
2,456✔
366
        _received_libmav_messages.emplace(ReceivedLibmavMessage{message, connection});
2,452✔
367
    }
2,456✔
368
    _received_libmav_messages_cv.notify_one();
2,455✔
369
}
2,458✔
370

371
void MavsdkImpl::process_messages()
31,669✔
372
{
373
    std::lock_guard lock(_received_messages_mutex);
31,669✔
374
    while (!_received_messages.empty()) {
33,857✔
375
        auto message_copied = _received_messages.front();
2,443✔
376
        process_message(message_copied.message, message_copied.connection_ptr);
2,440✔
377
        _received_messages.pop();
2,444✔
378
    }
379
}
31,195✔
380

381
void MavsdkImpl::process_libmav_messages()
31,172✔
382
{
383
    std::lock_guard lock(_received_libmav_messages_mutex);
31,172✔
384
    while (!_received_libmav_messages.empty()) {
33,499✔
385
        auto message_copied = _received_libmav_messages.front();
2,433✔
386
        process_libmav_message(message_copied.message, message_copied.connection_ptr);
2,438✔
387
        _received_libmav_messages.pop();
2,438✔
388
    }
2,439✔
389
}
30,805✔
390

391
void MavsdkImpl::process_message(mavlink_message_t& message, Connection* connection)
2,441✔
392
{
393
    // Assumes _received_messages_mutex
394

395
    if (_message_logging_on) {
2,441✔
396
        LogDebug() << "Processing message " << message.msgid << " from "
×
397
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
398
    }
399

400
    if (_should_exit) {
2,441✔
401
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
402
        return;
×
403
    }
404

405
    {
406
        std::lock_guard lock(_mutex);
2,441✔
407

408
        /** @note: Forward message FIRST (before intercept) if option is enabled and multiple
409
         * interfaces are connected. This ensures that forwarded messages are not affected by
410
         * intercept modifications. Performs message forwarding checks for every messages if message
411
         * forwarding is enabled on at least one connection, and in case of a single forwarding
412
         * connection, we check that it is not the one which received the current message.
413
         *
414
         * Conditions:
415
         * 1. At least 2 connections.
416
         * 2. At least 1 forwarding connection.
417
         * 3. At least 2 forwarding connections or current connection is not forwarding.
418
         */
419

420
        if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
2,496✔
421
            (mavsdk::Connection::forwarding_connections_count() > 1 ||
54✔
UNCOV
422
             !connection->should_forward_messages())) {
×
423
            if (_message_logging_on) {
54✔
424
                LogDebug() << "Forwarding message " << message.msgid << " from "
×
425
                           << static_cast<int>(message.sysid) << "/"
×
426
                           << static_cast<int>(message.compid);
×
427
            }
428
            forward_message(message, connection);
54✔
429
        }
430

431
        if (_should_exit) {
2,443✔
432
            // If we're meant to clean up, let's not try to acquire any more locks but bail.
433
            return;
×
434
        }
435

436
        // This is a low level interface where incoming messages can be tampered
437
        // with or even dropped FOR LOCAL PROCESSING ONLY (after forwarding).
438
        {
439
            bool keep = true;
2,440✔
440
            {
441
                std::lock_guard<std::mutex> intercept_lock(_intercept_callbacks_mutex);
2,440✔
442
                if (_intercept_incoming_messages_callback != nullptr) {
2,439✔
443
                    keep = _intercept_incoming_messages_callback(message);
248✔
444
                }
445
            }
2,439✔
446

447
            if (!keep) {
2,441✔
448
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
38✔
449
                return;
35✔
450
            }
451
        }
452

453
        // Don't ever create a system with sysid 0.
454
        if (message.sysid == 0) {
2,403✔
455
            if (_message_logging_on) {
×
456
                LogDebug() << "Ignoring message with sysid == 0";
×
457
            }
458
            return;
×
459
        }
460

461
        // Filter out messages by QGroundControl, however, only do that if MAVSDK
462
        // is also implementing a ground station and not if it is used in another
463
        // configuration, e.g. on a companion.
464
        //
465
        // This is a workaround because PX4 started forwarding messages between
466
        // mavlink instances which leads to existing implementations (including
467
        // examples and integration tests) to connect to QGroundControl by accident
468
        // instead of PX4 because the check `has_autopilot()` is not used.
469

470
        if (_configuration.get_component_type() == ComponentType::GroundStation &&
2,403✔
471
            message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
2,406✔
472
            if (_message_logging_on) {
×
473
                LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
474
            }
475
            return;
×
476
        }
477

478
        bool found_system = false;
2,406✔
479
        for (auto& system : _systems) {
2,446✔
480
            if (system.first == message.sysid) {
2,317✔
481
                system.second->system_impl()->add_new_component(message.compid);
2,277✔
482
                found_system = true;
2,277✔
483
                break;
2,277✔
484
            }
485
        }
486

487
        if (!found_system) {
2,408✔
488
            if (_system_debugging) {
131✔
489
                LogWarn() << "Create new system/component " << (int)message.sysid << "/"
×
490
                          << (int)message.compid;
×
491
                LogWarn() << "From message " << (int)message.msgid << " with len "
×
492
                          << (int)message.len;
×
493
                std::string bytes = "";
×
494
                for (unsigned i = 0; i < 12 + message.len; ++i) {
×
495
                    bytes += std::to_string(reinterpret_cast<uint8_t*>(&message)[i]) + ' ';
×
496
                }
497
                LogWarn() << "Bytes: " << bytes;
×
498
            }
×
499
            make_system_with_component(message.sysid, message.compid);
131✔
500

501
            // We now better talk back.
502
            start_sending_heartbeats();
131✔
503
        }
504

505
        if (_should_exit) {
2,408✔
506
            // Don't try to call at() if systems have already been destroyed
507
            // in destructor.
508
            return;
×
509
        }
510
    }
2,439✔
511

512
    mavlink_message_handler.process_message(message);
2,409✔
513

514
    for (auto& system : _systems) {
2,449✔
515
        if (system.first == message.sysid) {
2,448✔
516
            system.second->system_impl()->process_mavlink_message(message);
2,405✔
517
            break;
2,408✔
518
        }
519
    }
520
}
521

522
void MavsdkImpl::process_libmav_message(
2,437✔
523
    const Mavsdk::MavlinkMessage& message, Connection* /* connection */)
524
{
525
    // Assumes _received_libmav_messages_mutex
526

527
    if (_message_logging_on) {
2,437✔
528
        LogDebug() << "MavsdkImpl::process_libmav_message: " << message.message_name << " from "
×
529
                   << static_cast<int>(message.system_id) << "/"
×
530
                   << static_cast<int>(message.component_id);
×
531
    }
532

533
    // JSON message interception for incoming messages
534
    if (!call_json_interception_callbacks(message, _incoming_json_message_subscriptions)) {
2,437✔
535
        // Message was dropped by interception callback
536
        if (_message_logging_on) {
×
537
            LogDebug() << "Incoming JSON message " << message.message_name
×
538
                       << " dropped by interception";
×
539
        }
540
        return;
×
541
    }
542

543
    if (_message_logging_on) {
2,437✔
544
        LogDebug() << "Processing libmav message " << message.message_name << " from "
×
545
                   << static_cast<int>(message.system_id) << "/"
×
546
                   << static_cast<int>(message.component_id);
×
547
    }
548

549
    if (_should_exit) {
2,437✔
550
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
551
        return;
×
552
    }
553

554
    {
555
        std::lock_guard lock(_mutex);
2,437✔
556

557
        // Don't ever create a system with sysid 0.
558
        if (message.system_id == 0) {
2,435✔
559
            if (_message_logging_on) {
×
560
                LogDebug() << "Ignoring libmav message with sysid == 0";
×
561
            }
562
            return;
×
563
        }
564

565
        // Filter out QGroundControl messages similar to regular mavlink processing
566
        if (_configuration.get_component_type() == ComponentType::GroundStation &&
2,435✔
567
            message.system_id == 255 && message.component_id == MAV_COMP_ID_MISSIONPLANNER) {
2,431✔
568
            if (_message_logging_on) {
×
569
                LogDebug() << "Ignoring libmav messages from QGC as we are also a ground station";
×
570
            }
571
            return;
×
572
        }
573

574
        bool found_system = false;
2,431✔
575
        for (auto& system : _systems) {
2,472✔
576
            if (system.first == message.system_id) {
2,473✔
577
                system.second->system_impl()->add_new_component(message.component_id);
2,432✔
578
                found_system = true;
2,429✔
579
                break;
2,429✔
580
            }
581
        }
582

583
        if (!found_system) {
2,435✔
584
            if (_system_debugging) {
6✔
585
                LogWarn() << "Create new system/component from libmav " << (int)message.system_id
×
586
                          << "/" << (int)message.component_id;
×
587
            }
588
            make_system_with_component(message.system_id, message.component_id);
6✔
589

590
            // We now better talk back.
591
            start_sending_heartbeats();
6✔
592
        }
593

594
        if (_should_exit) {
2,435✔
595
            // Don't try to call at() if systems have already been destroyed
596
            // in destructor.
597
            return;
×
598
        }
599
    }
2,431✔
600

601
    // Distribute libmav message to systems for libmav-specific handling
602
    bool found_system = false;
2,434✔
603
    for (auto& system : _systems) {
4,947✔
604
        if (system.first == message.system_id) {
2,510✔
605
            if (_message_logging_on) {
2,434✔
606
                LogDebug() << "Distributing libmav message " << message.message_name
×
607
                           << " to SystemImpl for system " << system.first;
×
608
            }
609
            system.second->system_impl()->process_libmav_message(message);
2,434✔
610
            found_system = true;
2,437✔
611
            // Don't break - distribute to all matching system instances
612
        }
613
    }
614

615
    if (!found_system) {
2,439✔
616
        LogWarn() << "No system found for libmav message " << message.message_name
×
617
                  << " from system " << message.system_id;
×
618
    }
619
}
620

621
bool MavsdkImpl::send_message(mavlink_message_t& message)
2,582✔
622
{
623
    // Create a copy of the message to avoid reference issues
624
    mavlink_message_t message_copy = message;
2,582✔
625

626
    {
627
        std::lock_guard lock(_messages_to_send_mutex);
2,582✔
628
        _messages_to_send.push(std::move(message_copy));
2,578✔
629
    }
2,581✔
630

631
    // For heartbeat messages, we want to process them immediately to speed up system discovery
632
    if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
2,574✔
633
        // Trigger message processing in the work thread
634
        // This is a hint to process messages sooner, but doesn't block
635
        std::this_thread::yield();
438✔
636
    }
637

638
    return true;
2,581✔
639
}
640

641
void MavsdkImpl::deliver_messages()
34,172✔
642
{
643
    // Process messages one at a time to avoid holding the mutex while delivering
644
    while (true) {
645
        mavlink_message_t message;
646
        {
647
            std::lock_guard lock(_messages_to_send_mutex);
34,172✔
648
            if (_messages_to_send.empty()) {
33,620✔
649
                break;
30,996✔
650
            }
651
            message = _messages_to_send.front();
2,576✔
652
            _messages_to_send.pop();
2,579✔
653
        }
33,576✔
654
        deliver_message(message);
2,577✔
655
    }
2,583✔
656
}
30,864✔
657

658
void MavsdkImpl::deliver_message(mavlink_message_t& message)
2,582✔
659
{
660
    if (_message_logging_on) {
2,582✔
661
        LogDebug() << "Sending message " << message.msgid << " from "
×
662
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid)
×
663
                   << " to " << static_cast<int>(get_target_system_id(message)) << "/"
×
664
                   << static_cast<int>(get_target_component_id(message));
×
665
    }
666

667
    // This is a low level interface where outgoing messages can be tampered
668
    // with or even dropped.
669
    bool keep = true;
2,582✔
670
    {
671
        std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
2,582✔
672
        if (_intercept_outgoing_messages_callback != nullptr) {
2,580✔
673
            keep = _intercept_outgoing_messages_callback(message);
224✔
674
        }
675
    }
2,573✔
676

677
    if (!keep) {
2,579✔
678
        // We fake that everything was sent as instructed because
679
        // a potential loss would happen later, and we would not be informed
680
        // about it.
681
        LogDebug() << "Dropped outgoing message: " << int(message.msgid);
85✔
682
        return;
165✔
683
    }
684

685
    // JSON message interception for outgoing messages
686
    // Convert mavlink_message_t to Mavsdk::MavlinkMessage for JSON interception
687
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
688
    uint16_t len = mavlink_msg_to_send_buffer(buffer, &message);
2,494✔
689

690
    size_t bytes_consumed = 0;
2,496✔
691
    auto libmav_msg_opt = parse_message_safe(buffer, len, bytes_consumed);
2,496✔
692

693
    if (libmav_msg_opt) {
2,494✔
694
        // Create Mavsdk::MavlinkMessage directly for JSON interception
695
        Mavsdk::MavlinkMessage json_message;
2,492✔
696
        json_message.message_name = libmav_msg_opt.value().name();
2,491✔
697
        json_message.system_id = message.sysid;
2,491✔
698
        json_message.component_id = message.compid;
2,491✔
699

700
        // Extract target_system and target_component if present
701
        uint8_t target_system_id = 0;
2,491✔
702
        uint8_t target_component_id = 0;
2,491✔
703
        if (libmav_msg_opt.value().get("target_system", target_system_id) ==
2,491✔
704
            mav::MessageResult::Success) {
705
            json_message.target_system_id = target_system_id;
1,818✔
706
        } else {
707
            json_message.target_system_id = 0;
671✔
708
        }
709
        if (libmav_msg_opt.value().get("target_component", target_component_id) ==
2,489✔
710
            mav::MessageResult::Success) {
711
            json_message.target_component_id = target_component_id;
1,818✔
712
        } else {
713
            json_message.target_component_id = 0;
678✔
714
        }
715

716
        // Generate JSON using LibmavReceiver's public method
717
        auto connections = get_connections();
2,496✔
718
        if (!connections.empty() && connections[0]->get_libmav_receiver()) {
2,492✔
719
            json_message.fields_json =
720
                connections[0]->get_libmav_receiver()->libmav_message_to_json(
7,243✔
721
                    libmav_msg_opt.value());
4,832✔
722
        } else {
723
            // Fallback: create minimal JSON if no receiver available
724
            json_message.fields_json =
725
                "{\"message_id\":" + std::to_string(libmav_msg_opt.value().id()) +
160✔
726
                ",\"message_name\":\"" + libmav_msg_opt.value().name() + "\"}";
159✔
727
        }
728

729
        if (!call_json_interception_callbacks(json_message, _outgoing_json_message_subscriptions)) {
2,493✔
730
            // Message was dropped by JSON interception callback
731
            if (_message_logging_on) {
732
                LogDebug() << "Outgoing JSON message " << json_message.message_name
×
733
                           << " dropped by interception";
×
734
            }
735
            return;
×
736
        }
737
    }
2,495✔
738

739
    std::lock_guard lock(_mutex);
2,493✔
740

741
    if (_connections.empty()) {
2,491✔
742
        // We obviously can't send any messages without a connection added, so
743
        // we silently ignore this.
744
        return;
80✔
745
    }
746

747
    uint8_t successful_emissions = 0;
2,411✔
748
    for (auto& _connection : _connections) {
4,850✔
749
        const uint8_t target_system_id = get_target_system_id(message);
2,439✔
750

751
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
2,434✔
752
            continue;
11✔
753
        }
754
        const auto result = (*_connection.connection).send_message(message);
2,424✔
755
        if (result.first) {
2,429✔
756
            successful_emissions++;
2,424✔
757
        } else {
758
            _connections_errors_subscriptions.queue(
10✔
759
                Mavsdk::ConnectionError{result.second, _connection.handle},
5✔
760
                [this](const auto& func) { call_user_callback(func); });
×
761
        }
762
    }
2,429✔
763

764
    if (successful_emissions == 0) {
2,416✔
765
        LogErr() << "Sending message failed";
2✔
766
    }
767
}
2,498✔
768

769
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
138✔
770
    const std::string& connection_url, ForwardingOption forwarding_option)
771
{
772
    CliArg cli_arg;
138✔
773
    if (!cli_arg.parse(connection_url)) {
138✔
774
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
775
    }
776

777
    return std::visit(
138✔
778
        overloaded{
276✔
779
            [](std::monostate) {
×
780
                // Should not happen anyway.
781
                return std::pair<ConnectionResult, Mavsdk::ConnectionHandle>{
×
782
                    ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle()};
×
783
            },
784
            [this, forwarding_option](const CliArg::Udp& udp) {
130✔
785
                return add_udp_connection(udp, forwarding_option);
130✔
786
            },
787
            [this, forwarding_option](const CliArg::Tcp& tcp) {
8✔
788
                return add_tcp_connection(tcp, forwarding_option);
8✔
789
            },
790
            [this, forwarding_option](const CliArg::Serial& serial) {
×
791
                return add_serial_connection(
×
792
                    serial.path, serial.baudrate, serial.flow_control_enabled, forwarding_option);
×
793
            }},
794
        cli_arg.protocol);
138✔
795
}
138✔
796

797
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
798
MavsdkImpl::add_udp_connection(const CliArg::Udp& udp, ForwardingOption forwarding_option)
130✔
799
{
800
    auto new_conn = std::make_unique<UdpConnection>(
801
        [this](mavlink_message_t& message, Connection* connection) {
2,386✔
802
            receive_message(message, connection);
2,386✔
803
        },
2,388✔
804
        [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
2,384✔
805
            receive_libmav_message(message, connection);
2,384✔
806
        },
2,389✔
807
        *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
808
        udp.mode == CliArg::Udp::Mode::In ? udp.host : "0.0.0.0",
260✔
809
        udp.mode == CliArg::Udp::Mode::In ? udp.port : 0,
130✔
810
        forwarding_option);
130✔
811

812
    if (!new_conn) {
130✔
813
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
814
    }
815

816
    ConnectionResult ret = new_conn->start();
130✔
817

818
    if (ret != ConnectionResult::Success) {
130✔
819
        return {ret, Mavsdk::ConnectionHandle{}};
×
820
    }
821

822
    if (udp.mode == CliArg::Udp::Mode::Out) {
130✔
823
        // We need to add the IP rather than a hostname, otherwise we end up with two remotes:
824
        // one for the IP, and one for a hostname.
825
        auto remote_ip = resolve_hostname_to_ip(udp.host);
65✔
826

827
        if (!remote_ip) {
65✔
828
            return {ConnectionResult::DestinationIpUnknown, Mavsdk::ConnectionHandle{}};
×
829
        }
830

831
        new_conn->add_remote_to_keep(remote_ip.value(), udp.port);
65✔
832
        std::lock_guard lock(_mutex);
65✔
833

834
        // With a UDP remote, we need to initiate the connection by sending heartbeats.
835
        auto new_configuration = get_configuration();
65✔
836
        new_configuration.set_always_send_heartbeats(true);
65✔
837
        set_configuration(new_configuration);
65✔
838
    }
65✔
839

840
    auto handle = add_connection(std::move(new_conn));
130✔
841

842
    return {ConnectionResult::Success, handle};
130✔
843
}
130✔
844

845
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
846
MavsdkImpl::add_tcp_connection(const CliArg::Tcp& tcp, ForwardingOption forwarding_option)
8✔
847
{
848
    if (tcp.mode == CliArg::Tcp::Mode::Out) {
8✔
849
        auto new_conn = std::make_unique<TcpClientConnection>(
850
            [this](mavlink_message_t& message, Connection* connection) {
38✔
851
                receive_message(message, connection);
38✔
852
            },
38✔
853
            [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
38✔
854
                receive_libmav_message(message, connection);
38✔
855
            },
38✔
856
            *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
857
            tcp.host,
4✔
858
            tcp.port,
4✔
859
            forwarding_option);
4✔
860
        if (!new_conn) {
4✔
861
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
862
        }
863
        ConnectionResult ret = new_conn->start();
4✔
864
        if (ret == ConnectionResult::Success) {
4✔
865
            return {ret, add_connection(std::move(new_conn))};
4✔
866
        } else {
867
            return {ret, Mavsdk::ConnectionHandle{}};
×
868
        }
869
    } else {
4✔
870
        auto new_conn = std::make_unique<TcpServerConnection>(
871
            [this](mavlink_message_t& message, Connection* connection) {
33✔
872
                receive_message(message, connection);
33✔
873
            },
33✔
874
            [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
31✔
875
                receive_libmav_message(message, connection);
31✔
876
            },
31✔
877
            *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
878
            tcp.host,
4✔
879
            tcp.port,
4✔
880
            forwarding_option);
4✔
881
        if (!new_conn) {
4✔
882
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
883
        }
884
        ConnectionResult ret = new_conn->start();
4✔
885
        if (ret == ConnectionResult::Success) {
4✔
886
            return {ret, add_connection(std::move(new_conn))};
4✔
887
        } else {
888
            return {ret, Mavsdk::ConnectionHandle{}};
×
889
        }
890
    }
4✔
891
}
892

893
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
894
    const std::string& dev_path,
895
    int baudrate,
896
    bool flow_control,
897
    ForwardingOption forwarding_option)
898
{
899
    auto new_conn = std::make_unique<SerialConnection>(
900
        [this](mavlink_message_t& message, Connection* connection) {
×
901
            receive_message(message, connection);
×
902
        },
×
903
        [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
×
904
            receive_libmav_message(message, connection);
×
905
        },
×
906
        *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
907
        dev_path,
908
        baudrate,
909
        flow_control,
910
        forwarding_option);
×
911
    if (!new_conn) {
×
912
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
913
    }
914
    ConnectionResult ret = new_conn->start();
×
915
    if (ret == ConnectionResult::Success) {
×
916
        auto handle = add_connection(std::move(new_conn));
×
917

918
        auto new_configuration = get_configuration();
×
919

920
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
921
        // to initiate the MAVLink connection by sending heartbeats.
922
        // Therefore, we override the default here and enable sending heartbeats.
923
        new_configuration.set_always_send_heartbeats(true);
×
924
        set_configuration(new_configuration);
×
925

926
        return {ret, handle};
×
927

928
    } else {
929
        return {ret, Mavsdk::ConnectionHandle{}};
×
930
    }
931
}
×
932

933
Mavsdk::ConnectionHandle MavsdkImpl::add_connection(std::unique_ptr<Connection>&& new_connection)
138✔
934
{
935
    std::lock_guard lock(_mutex);
138✔
936
    auto handle = _connections_handle_factory.create();
138✔
937
    _connections.emplace_back(ConnectionEntry{std::move(new_connection), handle});
138✔
938

939
    return handle;
276✔
940
}
138✔
941

942
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
12✔
943
{
944
    std::lock_guard lock(_mutex);
12✔
945

946
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
12✔
947
        return (entry.handle == handle);
12✔
948
    }));
949
}
12✔
950

951
Mavsdk::Configuration MavsdkImpl::get_configuration() const
65✔
952
{
953
    std::lock_guard configuration_lock(_mutex);
65✔
954
    return _configuration;
130✔
955
}
65✔
956

957
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
197✔
958
{
959
    std::lock_guard server_components_lock(_server_components_mutex);
197✔
960
    // We just point the default to the newly created component. This means
961
    // that the previous default component will be deleted if it is not
962
    // used/referenced anywhere.
963
    _default_server_component =
964
        server_component_by_id_with_lock(new_configuration.get_component_id());
197✔
965

966
    if (new_configuration.get_always_send_heartbeats() &&
328✔
967
        !_configuration.get_always_send_heartbeats()) {
131✔
968
        start_sending_heartbeats();
69✔
969
    } else if (
128✔
970
        !new_configuration.get_always_send_heartbeats() &&
194✔
971
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
194✔
972
        stop_sending_heartbeats();
×
973
    }
974

975
    _configuration = new_configuration;
197✔
976
    // We cache these values as atomic to avoid having to lock any mutex for them.
977
    _our_system_id = new_configuration.get_system_id();
197✔
978
    _our_component_id = new_configuration.get_component_id();
197✔
979
}
197✔
980

981
uint8_t MavsdkImpl::get_own_system_id() const
5,839✔
982
{
983
    return _our_system_id;
5,839✔
984
}
985

986
uint8_t MavsdkImpl::get_own_component_id() const
1,440✔
987
{
988
    return _our_component_id;
1,440✔
989
}
990

991
uint8_t MavsdkImpl::channel() const
×
992
{
993
    // TODO
994
    return 0;
×
995
}
996

997
Autopilot MavsdkImpl::autopilot() const
×
998
{
999
    // TODO
1000
    return Autopilot::Px4;
×
1001
}
1002

1003
// FIXME: this should be per component
1004
uint8_t MavsdkImpl::get_mav_type() const
443✔
1005
{
1006
    return _configuration.get_mav_type();
443✔
1007
}
1008

1009
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
137✔
1010
{
1011
    // Needs _systems_lock
1012

1013
    if (_should_exit) {
137✔
1014
        // When the system got destroyed in the destructor, we have to give up.
1015
        return;
×
1016
    }
1017

1018
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
137✔
1019
        LogDebug() << "Initializing connection to remote system...";
×
1020
    } else {
1021
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
274✔
1022
                   << " Comp ID: " << static_cast<int>(comp_id);
137✔
1023
    }
1024

1025
    // Make a system with its first component
1026
    auto new_system = std::make_shared<System>(*this);
137✔
1027
    new_system->init(system_id, comp_id);
137✔
1028

1029
    _systems.emplace_back(system_id, new_system);
137✔
1030
}
137✔
1031

1032
void MavsdkImpl::notify_on_discover()
142✔
1033
{
1034
    // Queue the callbacks without holding the mutex to avoid deadlocks
1035
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
205✔
1036
}
142✔
1037

1038
void MavsdkImpl::notify_on_timeout()
5✔
1039
{
1040
    // Queue the callbacks without holding the mutex to avoid deadlocks
1041
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
5✔
1042
}
5✔
1043

1044
Mavsdk::NewSystemHandle
1045
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
62✔
1046
{
1047
    std::lock_guard lock(_mutex);
62✔
1048

1049
    const auto handle = _new_system_callbacks.subscribe(callback);
62✔
1050

1051
    if (is_any_system_connected()) {
62✔
1052
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
1053
    }
1054

1055
    return handle;
124✔
1056
}
62✔
1057

1058
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
61✔
1059
{
1060
    _new_system_callbacks.unsubscribe(handle);
61✔
1061
}
61✔
1062

1063
bool MavsdkImpl::is_any_system_connected() const
62✔
1064
{
1065
    std::vector<std::shared_ptr<System>> connected_systems = systems();
62✔
1066
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
62✔
1067
        return system->is_connected();
×
1068
    });
62✔
1069
}
62✔
1070

1071
void MavsdkImpl::work_thread()
132✔
1072
{
1073
    while (!_should_exit) {
31,568✔
1074
        // Process incoming messages
1075
        process_messages();
31,002✔
1076

1077
        // Process incoming libmav messages
1078
        process_libmav_messages();
31,132✔
1079

1080
        // Run timers
1081
        timeout_handler.run_once();
30,819✔
1082
        call_every_handler.run_once();
31,356✔
1083

1084
        // Do component work
1085
        {
1086
            std::lock_guard lock(_server_components_mutex);
31,379✔
1087
            for (auto& it : _server_components) {
62,623✔
1088
                if (it.second != nullptr) {
31,663✔
1089
                    it.second->_impl->do_work();
31,278✔
1090
                }
1091
            }
1092
        }
30,714✔
1093

1094
        // Deliver outgoing messages
1095
        deliver_messages();
30,971✔
1096

1097
        // If no messages to send, check if there are messages to receive
1098
        std::unique_lock lock_received(_received_messages_mutex);
31,016✔
1099
        if (_received_messages.empty()) {
31,079✔
1100
            // No messages to process, wait for a signal or timeout
1101
            _received_messages_cv.wait_for(lock_received, std::chrono::milliseconds(10), [this]() {
30,850✔
1102
                return !_received_messages.empty() || _should_exit;
62,559✔
1103
            });
1104
        }
1105
    }
31,529✔
1106
}
96✔
1107

1108
void MavsdkImpl::call_user_callback_located(
1,190✔
1109
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1110
{
1111
    // Don't enqueue callbacks if we're shutting down
1112
    if (_should_exit) {
1,190✔
1113
        return;
×
1114
    }
1115

1116
    auto callback_size = _user_callback_queue.size();
1,190✔
1117

1118
    if (_callback_tracker) {
1,190✔
NEW
1119
        _callback_tracker->record_queued(filename, linenumber);
×
NEW
1120
        _callback_tracker->maybe_print_stats(callback_size);
×
1121
    }
1122

1123
    if (callback_size >= 10) {
1,190✔
UNCOV
1124
        LogWarn()
×
NEW
1125
            << "User callback queue slow (queue size: " << callback_size
×
1126
            << ").\n"
UNCOV
1127
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1128

1129
    } else if (callback_size == 99) {
1,190✔
1130
        LogErr()
×
1131
            << "User callback queue overflown\n"
1132
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1133

1134
    } else if (callback_size >= 100) {
1,190✔
1135
        return;
×
1136
    }
1137

1138
    // We only need to keep track of filename and linenumber if we're actually debugging this.
1139
    UserCallback user_callback =
1140
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
2,380✔
1141

1142
    _user_callback_queue.push_back(std::make_shared<UserCallback>(user_callback));
1,190✔
1143
}
1,190✔
1144

1145
void MavsdkImpl::process_user_callbacks_thread()
132✔
1146
{
1147
    while (!_should_exit) {
1,454✔
1148
        UserCallback callback;
1,322✔
1149
        {
1150
            LockedQueue<UserCallback>::Guard guard(_user_callback_queue);
1,322✔
1151
            auto ptr = guard.wait_and_pop_front();
1,322✔
1152
            if (!ptr) {
1,322✔
1153
                continue;
132✔
1154
            }
1155
            // We need to get a copy instead of just a shared_ptr because the queue might
1156
            // be invalidated when the lock is released.
1157
            callback = *ptr;
1,190✔
1158
        }
1,454✔
1159

1160
        // Check if we're in the process of shutting down before executing the callback
1161
        if (_should_exit) {
1,190✔
1162
            continue;
×
1163
        }
1164

1165
        const double timeout_s = 1.0;
1,190✔
1166
        auto cookie = timeout_handler.add(
1,190✔
1167
            [&]() {
×
1168
                if (_callback_debugging) {
×
1169
                    LogWarn() << "Callback called from " << callback.filename << ":"
×
1170
                              << callback.linenumber << " took more than " << timeout_s
×
1171
                              << " second to run.";
×
1172
                    fflush(stdout);
×
1173
                    fflush(stderr);
×
1174
                    abort();
×
1175
                } else {
1176
                    LogWarn()
×
1177
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
1178
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1179
                }
1180
            },
×
1181
            timeout_s);
1182
        auto callback_start = std::chrono::steady_clock::now();
1,190✔
1183
        callback.func();
1,190✔
1184
        auto callback_end = std::chrono::steady_clock::now();
1,190✔
1185
        timeout_handler.remove(cookie);
1,190✔
1186

1187
        if (_callback_tracker) {
1,190✔
1188
            auto callback_duration_us =
NEW
1189
                std::chrono::duration_cast<std::chrono::microseconds>(callback_end - callback_start)
×
NEW
1190
                    .count();
×
NEW
1191
            _callback_tracker->record_executed(
×
1192
                callback.filename, callback.linenumber, callback_duration_us);
1193
        }
1194
    }
1,322✔
1195
}
132✔
1196

1197
void MavsdkImpl::start_sending_heartbeats()
348✔
1198
{
1199
    // Check if we're in the process of shutting down
1200
    if (_should_exit) {
348✔
1201
        return;
×
1202
    }
1203

1204
    // Before sending out first heartbeats we need to make sure we have a
1205
    // default server component.
1206
    default_server_component_impl();
348✔
1207

1208
    {
1209
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
348✔
1210
        call_every_handler.remove(_heartbeat_send_cookie);
348✔
1211
        _heartbeat_send_cookie =
348✔
1212
            call_every_handler.add([this]() { send_heartbeats(); }, HEARTBEAT_SEND_INTERVAL_S);
789✔
1213
    }
348✔
1214
}
1215

1216
void MavsdkImpl::stop_sending_heartbeats()
5✔
1217
{
1218
    if (!_configuration.get_always_send_heartbeats()) {
5✔
1219
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
1✔
1220
        call_every_handler.remove(_heartbeat_send_cookie);
1✔
1221
    }
1✔
1222
}
5✔
1223

1224
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
1,355✔
1225
{
1226
    std::lock_guard lock(_server_components_mutex);
1,355✔
1227
    return default_server_component_with_lock();
1,355✔
1228
}
1,355✔
1229

1230
ServerComponentImpl& MavsdkImpl::default_server_component_with_lock()
1,355✔
1231
{
1232
    if (_default_server_component == nullptr) {
1,355✔
1233
        _default_server_component = server_component_by_id_with_lock(_our_component_id);
×
1234
    }
1235
    return *_default_server_component->_impl;
1,355✔
1236
}
1237

1238
void MavsdkImpl::send_heartbeats()
430✔
1239
{
1240
    std::lock_guard lock(_server_components_mutex);
430✔
1241

1242
    for (auto& it : _server_components) {
869✔
1243
        if (it.second != nullptr) {
437✔
1244
            it.second->_impl->send_heartbeat();
439✔
1245
        }
1246
    }
1247
}
429✔
1248

1249
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
24✔
1250
{
1251
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
24✔
1252
    _intercept_incoming_messages_callback = callback;
24✔
1253
}
24✔
1254

1255
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
1256
{
1257
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
14✔
1258
    _intercept_outgoing_messages_callback = callback;
14✔
1259
}
14✔
1260

1261
bool MavsdkImpl::call_json_interception_callbacks(
4,933✔
1262
    const Mavsdk::MavlinkMessage& json_message,
1263
    std::vector<std::pair<Mavsdk::InterceptJsonHandle, Mavsdk::InterceptJsonCallback>>&
1264
        callback_list)
1265
{
1266
    bool keep_message = true;
4,933✔
1267

1268
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
4,933✔
1269
    for (const auto& subscription : callback_list) {
4,938✔
1270
        if (!subscription.second(json_message)) {
8✔
1271
            keep_message = false;
×
1272
        }
1273
    }
1274

1275
    return keep_message;
9,849✔
1276
}
4,915✔
1277

1278
Mavsdk::InterceptJsonHandle
1279
MavsdkImpl::subscribe_incoming_messages_json(const Mavsdk::InterceptJsonCallback& callback)
1✔
1280
{
1281
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1282
    auto handle = _json_handle_factory.create();
1✔
1283
    _incoming_json_message_subscriptions.push_back(std::make_pair(handle, callback));
1✔
1284
    return handle;
2✔
1285
}
1✔
1286

1287
void MavsdkImpl::unsubscribe_incoming_messages_json(Mavsdk::InterceptJsonHandle handle)
1✔
1288
{
1289
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1290
    auto it = std::find_if(
1✔
1291
        _incoming_json_message_subscriptions.begin(),
1292
        _incoming_json_message_subscriptions.end(),
1293
        [handle](const auto& subscription) { return subscription.first == handle; });
1✔
1294
    if (it != _incoming_json_message_subscriptions.end()) {
1✔
1295
        _incoming_json_message_subscriptions.erase(it);
1✔
1296
    }
1297
}
1✔
1298

1299
Mavsdk::InterceptJsonHandle
1300
MavsdkImpl::subscribe_outgoing_messages_json(const Mavsdk::InterceptJsonCallback& callback)
1✔
1301
{
1302
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1303
    auto handle = _json_handle_factory.create();
1✔
1304
    _outgoing_json_message_subscriptions.push_back(std::make_pair(handle, callback));
1✔
1305
    return handle;
2✔
1306
}
1✔
1307

1308
void MavsdkImpl::unsubscribe_outgoing_messages_json(Mavsdk::InterceptJsonHandle handle)
1✔
1309
{
1310
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1311
    auto it = std::find_if(
1✔
1312
        _outgoing_json_message_subscriptions.begin(),
1313
        _outgoing_json_message_subscriptions.end(),
1314
        [handle](const auto& subscription) { return subscription.first == handle; });
1✔
1315
    if (it != _outgoing_json_message_subscriptions.end()) {
1✔
1316
        _outgoing_json_message_subscriptions.erase(it);
1✔
1317
    }
1318
}
1✔
1319

1320
Mavsdk::ConnectionErrorHandle
1321
MavsdkImpl::subscribe_connection_errors(Mavsdk::ConnectionErrorCallback callback)
×
1322
{
1323
    std::lock_guard lock(_mutex);
×
1324

1325
    const auto handle = _connections_errors_subscriptions.subscribe(callback);
×
1326

1327
    return handle;
×
1328
}
×
1329

1330
void MavsdkImpl::unsubscribe_connection_errors(Mavsdk::ConnectionErrorHandle handle)
×
1331
{
1332
    std::lock_guard lock(_mutex);
×
1333
    _connections_errors_subscriptions.unsubscribe(handle);
×
1334
}
×
1335

1336
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
2,494✔
1337
{
1338
    // Checks whether connection knows target system ID by extracting target system if set.
1339
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
2,494✔
1340

1341
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
2,486✔
1342
        return 0;
633✔
1343
    }
1344

1345
    // Don't look at the target system offset if it is outside the payload length.
1346
    // This can happen if the fields are trimmed.
1347
    if (meta->target_system_ofs >= message.len) {
1,853✔
1348
        return 0;
33✔
1349
    }
1350

1351
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,820✔
1352
}
1353

1354
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
54✔
1355
{
1356
    // Checks whether connection knows target system ID by extracting target system if set.
1357
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
54✔
1358

1359
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
54✔
1360
        return 0;
29✔
1361
    }
1362

1363
    // Don't look at the target component offset if it is outside the payload length.
1364
    // This can happen if the fields are trimmed.
1365
    if (meta->target_component_ofs >= message.len) {
25✔
1366
        return 0;
4✔
1367
    }
1368

1369
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
21✔
1370
}
1371

1372
Sender& MavsdkImpl::sender()
×
1373
{
1374
    std::lock_guard lock(_server_components_mutex);
×
1375
    return default_server_component_with_lock().sender();
×
1376
}
×
1377

1378
std::vector<Connection*> MavsdkImpl::get_connections() const
2,496✔
1379
{
1380
    std::lock_guard lock(_mutex);
2,496✔
1381
    std::vector<Connection*> connections;
2,493✔
1382
    for (const auto& connection_entry : _connections) {
4,920✔
1383
        connections.push_back(connection_entry.connection.get());
2,440✔
1384
    }
1385
    return connections;
2,490✔
1386
}
2,490✔
1387

1388
mav::MessageSet& MavsdkImpl::get_message_set() const
23✔
1389
{
1390
    // Note: This returns a reference to MessageSet without locking.
1391
    // Thread safety for MessageSet operations must be ensured by:
1392
    // 1. Using load_custom_xml_to_message_set() for write operations (XML loading)
1393
    // 2. libmav MessageSet should be internally thread-safe for read operations
1394
    // 3. If race conditions persist, consider implementing a thread-safe MessageSet wrapper
1395
    return *_message_set;
23✔
1396
}
1397

1398
bool MavsdkImpl::load_custom_xml_to_message_set(const std::string& xml_content)
6✔
1399
{
1400
    std::lock_guard<std::mutex> lock(_message_set_mutex);
6✔
1401
    auto result = _message_set->addFromXMLString(xml_content, false /* recursive_open_includes */);
6✔
1402
    return result == ::mav::MessageSetResult::Success;
12✔
1403
}
6✔
1404

1405
// Thread-safe MessageSet read operations
1406
std::optional<std::string> MavsdkImpl::message_id_to_name_safe(uint32_t id) const
×
1407
{
1408
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1409
    auto message_def = _message_set->getMessageDefinition(static_cast<int>(id));
×
1410
    if (message_def) {
×
1411
        return message_def.get().name();
×
1412
    }
1413
    return std::nullopt;
×
1414
}
×
1415

1416
std::optional<int> MavsdkImpl::message_name_to_id_safe(const std::string& name) const
×
1417
{
1418
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1419
    return _message_set->idForMessage(name);
×
1420
}
×
1421

1422
std::optional<mav::Message> MavsdkImpl::create_message_safe(const std::string& message_name) const
×
1423
{
1424
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1425
    return _message_set->create(message_name);
×
1426
}
×
1427

1428
// Thread-safe parsing for LibmavReceiver
1429
std::optional<mav::Message> MavsdkImpl::parse_message_safe(
4,943✔
1430
    const uint8_t* buffer, size_t buffer_len, size_t& bytes_consumed) const
1431
{
1432
    std::lock_guard<std::mutex> lock(_message_set_mutex);
4,943✔
1433
    return _buffer_parser->parseMessage(buffer, buffer_len, bytes_consumed);
4,951✔
1434
}
4,946✔
1435

1436
mav::OptionalReference<const mav::MessageDefinition>
1437
MavsdkImpl::get_message_definition_safe(int message_id) const
4,862✔
1438
{
1439
    std::lock_guard<std::mutex> lock(_message_set_mutex);
4,862✔
1440
    return _message_set->getMessageDefinition(message_id);
4,866✔
1441
}
4,874✔
1442

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