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

mavlink / MAVSDK / 20560534171

28 Dec 2025 10:39PM UTC coverage: 48.047% (-0.03%) from 48.078%
20560534171

Pull #2746

github

web-flow
Merge bb2347827 into 2460e1568
Pull Request #2746: Configuration and component cleanup

18 of 45 new or added lines in 4 files covered. (40.0%)

13 existing lines in 6 files now uncovered.

17741 of 36924 relevant lines covered (48.05%)

464.81 hits per line

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

71.24
/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
    const auto mav_type = Mavsdk::Configuration::mav_type_for_component_type(server_component_type);
54✔
228

229
    switch (server_component_type) {
54✔
230
        case ComponentType::Autopilot:
40✔
231
            if (instance == 0) {
40✔
232
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1, mav_type);
40✔
233
            } else {
234
                LogErr() << "Only autopilot instance 0 is valid";
×
235
                return {};
×
236
            }
237

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

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

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

NEW
278
        case ComponentType::Gimbal:
×
NEW
279
            if (instance == 0) {
×
NEW
280
                return server_component_by_id(MAV_COMP_ID_GIMBAL, mav_type);
×
281
            } else {
NEW
282
                LogErr() << "Only gimbal instance 0 is valid";
×
NEW
283
                return {};
×
284
            }
285

NEW
286
        case ComponentType::RemoteId:
×
NEW
287
            if (instance == 0) {
×
NEW
288
                return server_component_by_id(MAV_COMP_ID_ODID_TXRX_1, mav_type);
×
289
            } else {
NEW
290
                LogErr() << "Only remote ID instance 0 is valid";
×
NEW
291
                return {};
×
292
            }
293

NEW
294
        case ComponentType::Custom:
×
NEW
295
            LogErr() << "Custom component type requires explicit component ID";
×
NEW
296
            return {};
×
297

298
        default:
×
299
            LogErr() << "Unknown server component type";
×
300
            return {};
×
301
    }
302
}
303

304
std::shared_ptr<ServerComponent>
305
MavsdkImpl::server_component_by_id(uint8_t component_id, uint8_t mav_type)
54✔
306
{
307
    if (component_id == 0) {
54✔
308
        LogErr() << "Server component with component ID 0 not allowed";
×
309
        return nullptr;
×
310
    }
311

312
    std::lock_guard lock(_server_components_mutex);
54✔
313

314
    return server_component_by_id_with_lock(component_id, mav_type);
54✔
315
}
54✔
316

317
std::shared_ptr<ServerComponent>
318
MavsdkImpl::server_component_by_id_with_lock(uint8_t component_id, uint8_t mav_type)
261✔
319
{
320
    for (auto& it : _server_components) {
262✔
321
        if (it.first == component_id) {
123✔
322
            if (it.second != nullptr) {
122✔
323
                return it.second;
122✔
324
            } else {
NEW
325
                it.second = std::make_shared<ServerComponent>(*this, component_id, mav_type);
×
326
            }
327
        }
328
    }
329

330
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
139✔
331
        component_id, std::make_shared<ServerComponent>(*this, component_id, mav_type)));
278✔
332

333
    return _server_components.back().second;
139✔
334
}
335

336
void MavsdkImpl::forward_message(mavlink_message_t& message, Connection* connection)
51✔
337
{
338
    // Forward_message Function implementing Mavlink routing rules.
339
    // See https://mavlink.io/en/guide/routing.html
340

341
    bool forward_heartbeats_enabled = true;
51✔
342
    const uint8_t target_system_id = get_target_system_id(message);
51✔
343
    const uint8_t target_component_id = get_target_component_id(message);
51✔
344

345
    // If it's a message only for us, we keep it, otherwise, we forward it.
346
    const bool targeted_only_at_us =
347
        (target_system_id == get_own_system_id() && target_component_id == get_own_component_id());
51✔
348

349
    // We don't forward heartbeats unless it's specifically enabled.
350
    const bool heartbeat_check_ok =
51✔
351
        (message.msgid != MAVLINK_MSG_ID_HEARTBEAT || forward_heartbeats_enabled);
51✔
352

353
    if (!targeted_only_at_us && heartbeat_check_ok) {
51✔
354
        unsigned successful_emissions = 0;
41✔
355
        for (auto& entry : _connections) {
120✔
356
            // Check whether the connection is not the one from which we received the message.
357
            // And also check if the connection was set to forward messages.
358
            if (entry.connection.get() == connection ||
117✔
359
                !entry.connection->should_forward_messages()) {
38✔
360
                continue;
41✔
361
            }
362
            auto result = (*entry.connection).send_message(message);
38✔
363
            if (result.first) {
38✔
364
                successful_emissions++;
37✔
365
            } else {
366
                _connections_errors_subscriptions.queue(
2✔
367
                    Mavsdk::ConnectionError{result.second, entry.handle},
1✔
368
                    [this](const auto& func) { call_user_callback(func); });
×
369
            }
370
        }
38✔
371
        if (successful_emissions == 0) {
41✔
372
            if (_system_debugging) {
4✔
373
                LogErr() << "Message forwarding failed";
×
374
            }
375
        }
376
    }
377
}
51✔
378

379
void MavsdkImpl::receive_message(
2,495✔
380
    MavlinkReceiver::ParseResult result, mavlink_message_t& message, Connection* connection)
381
{
382
    if (result == MavlinkReceiver::ParseResult::MessageParsed) {
2,495✔
383
        // Valid message: queue for full processing (which includes forwarding)
384
        {
385
            std::lock_guard lock(_received_messages_mutex);
2,495✔
386
            _received_messages.emplace(ReceivedMessage{std::move(message), connection});
2,496✔
387
        }
2,499✔
388
        _received_messages_cv.notify_one();
2,496✔
389

UNCOV
390
    } else if (result == MavlinkReceiver::ParseResult::BadCrc) {
×
391
        // Unknown message: forward only, don't process locally
392
        forward_message(message, connection);
4✔
393
    }
394
}
2,500✔
395

396
void MavsdkImpl::receive_libmav_message(
2,496✔
397
    const Mavsdk::MavlinkMessage& message, Connection* connection)
398
{
399
    {
400
        std::lock_guard lock(_received_libmav_messages_mutex);
2,496✔
401
        _received_libmav_messages.emplace(ReceivedLibmavMessage{message, connection});
2,499✔
402
    }
2,503✔
403
    _received_libmav_messages_cv.notify_one();
2,501✔
404
}
2,503✔
405

406
void MavsdkImpl::process_messages()
32,077✔
407
{
408
    std::lock_guard lock(_received_messages_mutex);
32,077✔
409
    while (!_received_messages.empty()) {
34,300✔
410
        auto message_copied = _received_messages.front();
2,479✔
411
        process_message(message_copied.message, message_copied.connection_ptr);
2,474✔
412
        _received_messages.pop();
2,481✔
413
    }
414
}
31,219✔
415

416
void MavsdkImpl::process_libmav_messages()
31,615✔
417
{
418
    std::lock_guard lock(_received_libmav_messages_mutex);
31,615✔
419
    while (!_received_libmav_messages.empty()) {
33,783✔
420
        auto message_copied = _received_libmav_messages.front();
2,482✔
421
        process_libmav_message(message_copied.message, message_copied.connection_ptr);
2,480✔
422
        _received_libmav_messages.pop();
2,482✔
423
    }
2,480✔
424
}
31,486✔
425

426
void MavsdkImpl::process_message(mavlink_message_t& message, Connection* connection)
2,477✔
427
{
428
    // Assumes _received_messages_mutex
429

430
    if (_message_logging_on) {
2,477✔
431
        LogDebug() << "Processing message " << message.msgid << " from "
×
432
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
433
    }
434

435
    if (_should_exit) {
2,477✔
436
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
437
        return;
×
438
    }
439

440
    {
441
        std::lock_guard lock(_mutex);
2,477✔
442

443
        /** @note: Forward message FIRST (before intercept) if option is enabled and multiple
444
         * interfaces are connected. This ensures that forwarded messages are not affected by
445
         * intercept modifications. Performs message forwarding checks for every messages if message
446
         * forwarding is enabled on at least one connection, and in case of a single forwarding
447
         * connection, we check that it is not the one which received the current message.
448
         *
449
         * Conditions:
450
         * 1. At least 2 connections.
451
         * 2. At least 1 forwarding connection.
452
         * 3. At least 2 forwarding connections or current connection is not forwarding.
453
         */
454

455
        if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
2,526✔
456
            (mavsdk::Connection::forwarding_connections_count() > 1 ||
47✔
457
             !connection->should_forward_messages())) {
458
            if (_message_logging_on) {
47✔
459
                LogDebug() << "Forwarding message " << message.msgid << " from "
×
460
                           << static_cast<int>(message.sysid) << "/"
×
461
                           << static_cast<int>(message.compid);
×
462
            }
463
            forward_message(message, connection);
47✔
464
        }
465

466
        if (_should_exit) {
2,480✔
467
            // If we're meant to clean up, let's not try to acquire any more locks but bail.
468
            return;
×
469
        }
470

471
        // This is a low level interface where incoming messages can be tampered
472
        // with or even dropped FOR LOCAL PROCESSING ONLY (after forwarding).
473
        {
474
            bool keep = true;
2,474✔
475
            {
476
                std::lock_guard<std::mutex> intercept_lock(_intercept_callbacks_mutex);
2,474✔
477
                if (_intercept_incoming_messages_callback != nullptr) {
2,481✔
478
                    keep = _intercept_incoming_messages_callback(message);
249✔
479
                }
480
            }
2,475✔
481

482
            if (!keep) {
2,480✔
483
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
37✔
484
                return;
35✔
485
            }
486
        }
487

488
        // Don't ever create a system with sysid 0.
489
        if (message.sysid == 0) {
2,443✔
490
            if (_message_logging_on) {
×
491
                LogDebug() << "Ignoring message with sysid == 0";
×
492
            }
493
            return;
×
494
        }
495

496
        // Filter out messages by QGroundControl, however, only do that if MAVSDK
497
        // is also implementing a ground station and not if it is used in another
498
        // configuration, e.g. on a companion.
499
        //
500
        // This is a workaround because PX4 started forwarding messages between
501
        // mavlink instances which leads to existing implementations (including
502
        // examples and integration tests) to connect to QGroundControl by accident
503
        // instead of PX4 because the check `has_autopilot()` is not used.
504

505
        if (_configuration.get_component_type() == ComponentType::GroundStation &&
2,443✔
506
            message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
2,436✔
507
            if (_message_logging_on) {
×
508
                LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
509
            }
510
            return;
×
511
        }
512

513
        bool found_system = false;
2,436✔
514
        for (auto& system : _systems) {
2,464✔
515
            if (system.first == message.sysid) {
2,335✔
516
                system.second->system_impl()->add_new_component(message.compid);
2,307✔
517
                found_system = true;
2,303✔
518
                break;
2,303✔
519
            }
520
        }
521

522
        if (!found_system) {
2,438✔
523
            if (_system_debugging) {
136✔
524
                LogWarn() << "Create new system/component " << (int)message.sysid << "/"
×
525
                          << (int)message.compid;
×
526
                LogWarn() << "From message " << (int)message.msgid << " with len "
×
527
                          << (int)message.len;
×
528
                std::string bytes = "";
×
529
                for (unsigned i = 0; i < 12 + message.len; ++i) {
×
530
                    bytes += std::to_string(reinterpret_cast<uint8_t*>(&message)[i]) + ' ';
×
531
                }
532
                LogWarn() << "Bytes: " << bytes;
×
533
            }
×
534
            make_system_with_component(message.sysid, message.compid);
136✔
535

536
            // We now better talk back.
537
            start_sending_heartbeats();
136✔
538
        }
539

540
        if (_should_exit) {
2,438✔
541
            // Don't try to call at() if systems have already been destroyed
542
            // in destructor.
543
            return;
×
544
        }
545
    }
2,477✔
546

547
    mavlink_message_handler.process_message(message);
2,443✔
548

549
    for (auto& system : _systems) {
2,481✔
550
        if (system.first == message.sysid) {
2,480✔
551
            system.second->system_impl()->process_mavlink_message(message);
2,442✔
552
            break;
2,447✔
553
        }
554
    }
555
}
556

557
void MavsdkImpl::process_libmav_message(
2,482✔
558
    const Mavsdk::MavlinkMessage& message, Connection* /* connection */)
559
{
560
    // Assumes _received_libmav_messages_mutex
561

562
    if (_message_logging_on) {
2,482✔
563
        LogDebug() << "MavsdkImpl::process_libmav_message: " << message.message_name << " from "
×
564
                   << static_cast<int>(message.system_id) << "/"
×
565
                   << static_cast<int>(message.component_id);
×
566
    }
567

568
    // JSON message interception for incoming messages
569
    if (!call_json_interception_callbacks(message, _incoming_json_message_subscriptions)) {
2,482✔
570
        // Message was dropped by interception callback
571
        if (_message_logging_on) {
×
572
            LogDebug() << "Incoming JSON message " << message.message_name
×
573
                       << " dropped by interception";
×
574
        }
575
        return;
×
576
    }
577

578
    if (_message_logging_on) {
2,477✔
579
        LogDebug() << "Processing libmav message " << message.message_name << " from "
×
580
                   << static_cast<int>(message.system_id) << "/"
×
581
                   << static_cast<int>(message.component_id);
×
582
    }
583

584
    if (_should_exit) {
2,477✔
585
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
586
        return;
×
587
    }
588

589
    {
590
        std::lock_guard lock(_mutex);
2,477✔
591

592
        // Don't ever create a system with sysid 0.
593
        if (message.system_id == 0) {
2,477✔
594
            if (_message_logging_on) {
×
595
                LogDebug() << "Ignoring libmav message with sysid == 0";
×
596
            }
597
            return;
×
598
        }
599

600
        // Filter out QGroundControl messages similar to regular mavlink processing
601
        if (_configuration.get_component_type() == ComponentType::GroundStation &&
2,477✔
602
            message.system_id == 255 && message.component_id == MAV_COMP_ID_MISSIONPLANNER) {
2,473✔
603
            if (_message_logging_on) {
×
604
                LogDebug() << "Ignoring libmav messages from QGC as we are also a ground station";
×
605
            }
606
            return;
×
607
        }
608

609
        bool found_system = false;
2,473✔
610
        for (auto& system : _systems) {
2,508✔
611
            if (system.first == message.system_id) {
2,510✔
612
                system.second->system_impl()->add_new_component(message.component_id);
2,475✔
613
                found_system = true;
2,475✔
614
                break;
2,475✔
615
            }
616
        }
617

618
        if (!found_system) {
2,483✔
619
            if (_system_debugging) {
6✔
620
                LogWarn() << "Create new system/component from libmav " << (int)message.system_id
×
621
                          << "/" << (int)message.component_id;
×
622
            }
623
            make_system_with_component(message.system_id, message.component_id);
6✔
624

625
            // We now better talk back.
626
            start_sending_heartbeats();
6✔
627
        }
628

629
        if (_should_exit) {
2,483✔
630
            // Don't try to call at() if systems have already been destroyed
631
            // in destructor.
632
            return;
×
633
        }
634
    }
2,473✔
635

636
    // Distribute libmav message to systems for libmav-specific handling
637
    bool found_system = false;
2,478✔
638
    for (auto& system : _systems) {
5,026✔
639
        if (system.first == message.system_id) {
2,540✔
640
            if (_message_logging_on) {
2,472✔
641
                LogDebug() << "Distributing libmav message " << message.message_name
×
642
                           << " to SystemImpl for system " << system.first;
×
643
            }
644
            system.second->system_impl()->process_libmav_message(message);
2,472✔
645
            found_system = true;
2,480✔
646
            // Don't break - distribute to all matching system instances
647
        }
648
    }
649

650
    if (!found_system) {
2,480✔
651
        LogWarn() << "No system found for libmav message " << message.message_name
×
652
                  << " from system " << message.system_id;
×
653
    }
654
}
655

656
bool MavsdkImpl::send_message(mavlink_message_t& message)
2,635✔
657
{
658
    // Create a copy of the message to avoid reference issues
659
    mavlink_message_t message_copy = message;
2,635✔
660

661
    {
662
        std::lock_guard lock(_messages_to_send_mutex);
2,635✔
663
        _messages_to_send.push(std::move(message_copy));
2,629✔
664
    }
2,635✔
665

666
    // For heartbeat messages, we want to process them immediately to speed up system discovery
667
    if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
2,632✔
668
        // Trigger message processing in the work thread
669
        // This is a hint to process messages sooner, but doesn't block
670
        std::this_thread::yield();
453✔
671
    }
672

673
    return true;
2,638✔
674
}
675

676
void MavsdkImpl::deliver_messages()
34,576✔
677
{
678
    // Process messages one at a time to avoid holding the mutex while delivering
679
    while (true) {
680
        mavlink_message_t message;
681
        {
682
            std::lock_guard lock(_messages_to_send_mutex);
34,576✔
683
            if (_messages_to_send.empty()) {
33,968✔
684
                break;
31,671✔
685
            }
686
            message = _messages_to_send.front();
2,633✔
687
            _messages_to_send.pop();
2,635✔
688
        }
34,305✔
689
        deliver_message(message);
2,635✔
690
    }
2,638✔
691
}
31,143✔
692

693
void MavsdkImpl::deliver_message(mavlink_message_t& message)
2,638✔
694
{
695
    if (_message_logging_on) {
2,638✔
696
        LogDebug() << "Sending message " << message.msgid << " from "
×
697
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid)
×
698
                   << " to " << static_cast<int>(get_target_system_id(message)) << "/"
×
699
                   << static_cast<int>(get_target_component_id(message));
×
700
    }
701

702
    // This is a low level interface where outgoing messages can be tampered
703
    // with or even dropped.
704
    bool keep = true;
2,638✔
705
    {
706
        std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
2,638✔
707
        if (_intercept_outgoing_messages_callback != nullptr) {
2,636✔
708
            keep = _intercept_outgoing_messages_callback(message);
227✔
709
        }
710
    }
2,627✔
711

712
    if (!keep) {
2,635✔
713
        // We fake that everything was sent as instructed because
714
        // a potential loss would happen later, and we would not be informed
715
        // about it.
716
        LogDebug() << "Dropped outgoing message: " << int(message.msgid);
86✔
717
        return;
169✔
718
    }
719

720
    // JSON message interception for outgoing messages
721
    // Convert mavlink_message_t to Mavsdk::MavlinkMessage for JSON interception
722
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
723
    uint16_t len = mavlink_msg_to_send_buffer(buffer, &message);
2,549✔
724

725
    size_t bytes_consumed = 0;
2,552✔
726
    auto libmav_msg_opt = parse_message_safe(buffer, len, bytes_consumed);
2,552✔
727

728
    if (libmav_msg_opt) {
2,550✔
729
        // Create Mavsdk::MavlinkMessage directly for JSON interception
730
        Mavsdk::MavlinkMessage json_message;
2,552✔
731
        json_message.message_name = libmav_msg_opt.value().name();
2,544✔
732
        json_message.system_id = message.sysid;
2,545✔
733
        json_message.component_id = message.compid;
2,545✔
734

735
        // Extract target_system and target_component if present
736
        uint8_t target_system_id = 0;
2,545✔
737
        uint8_t target_component_id = 0;
2,545✔
738
        if (libmav_msg_opt.value().get("target_system", target_system_id) ==
2,545✔
739
            mav::MessageResult::Success) {
740
            json_message.target_system_id = target_system_id;
1,849✔
741
        } else {
742
            json_message.target_system_id = 0;
693✔
743
        }
744
        if (libmav_msg_opt.value().get("target_component", target_component_id) ==
2,542✔
745
            mav::MessageResult::Success) {
746
            json_message.target_component_id = target_component_id;
1,849✔
747
        } else {
748
            json_message.target_component_id = 0;
698✔
749
        }
750

751
        // Generate JSON using LibmavReceiver's public method
752
        auto connections = get_connections();
2,547✔
753
        if (!connections.empty() && connections[0]->get_libmav_receiver()) {
2,549✔
754
            json_message.fields_json =
755
                connections[0]->get_libmav_receiver()->libmav_message_to_json(
7,396✔
756
                    libmav_msg_opt.value());
4,935✔
757
        } else {
758
            // Fallback: create minimal JSON if no receiver available
759
            json_message.fields_json =
760
                "{\"message_id\":" + std::to_string(libmav_msg_opt.value().id()) +
166✔
761
                ",\"message_name\":\"" + libmav_msg_opt.value().name() + "\"}";
166✔
762
        }
763

764
        if (!call_json_interception_callbacks(json_message, _outgoing_json_message_subscriptions)) {
2,552✔
765
            // Message was dropped by JSON interception callback
766
            if (_message_logging_on) {
767
                LogDebug() << "Outgoing JSON message " << json_message.message_name
×
768
                           << " dropped by interception";
×
769
            }
770
            return;
×
771
        }
772
    }
2,543✔
773

774
    std::lock_guard lock(_mutex);
2,546✔
775

776
    if (_connections.empty()) {
2,546✔
777
        // We obviously can't send any messages without a connection added, so
778
        // we silently ignore this.
779
        return;
83✔
780
    }
781

782
    uint8_t successful_emissions = 0;
2,457✔
783
    for (auto& _connection : _connections) {
4,941✔
784
        const uint8_t target_system_id = get_target_system_id(message);
2,487✔
785

786
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
2,482✔
787
            continue;
8✔
788
        }
789
        const auto result = (*_connection.connection).send_message(message);
2,473✔
790
        if (result.first) {
2,480✔
791
            successful_emissions++;
2,474✔
792
        } else {
793
            _connections_errors_subscriptions.queue(
12✔
794
                Mavsdk::ConnectionError{result.second, _connection.handle},
6✔
795
                [this](const auto& func) { call_user_callback(func); });
×
796
        }
797
    }
2,480✔
798

799
    if (successful_emissions == 0) {
2,465✔
800
        LogErr() << "Sending message failed";
4✔
801
    }
802
}
2,551✔
803

804
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
144✔
805
    const std::string& connection_url, ForwardingOption forwarding_option)
806
{
807
    CliArg cli_arg;
144✔
808
    if (!cli_arg.parse(connection_url)) {
144✔
809
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
810
    }
811

812
    return std::visit(
144✔
813
        overloaded{
288✔
814
            [](std::monostate) {
×
815
                // Should not happen anyway.
816
                return std::pair<ConnectionResult, Mavsdk::ConnectionHandle>{
×
817
                    ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle()};
×
818
            },
819
            [this, forwarding_option](const CliArg::Udp& udp) {
134✔
820
                return add_udp_connection(udp, forwarding_option);
134✔
821
            },
822
            [this, forwarding_option](const CliArg::Tcp& tcp) {
8✔
823
                return add_tcp_connection(tcp, forwarding_option);
8✔
824
            },
825
            [this, forwarding_option](const CliArg::Serial& serial) {
×
826
                return add_serial_connection(
×
827
                    serial.path, serial.baudrate, serial.flow_control_enabled, forwarding_option);
×
828
            },
829
            [this, forwarding_option](const CliArg::Raw&) {
2✔
830
                return add_raw_connection(forwarding_option);
2✔
831
            }},
832
        cli_arg.protocol);
144✔
833
}
144✔
834

835
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
836
MavsdkImpl::add_udp_connection(const CliArg::Udp& udp, ForwardingOption forwarding_option)
134✔
837
{
838
    auto new_conn = std::make_unique<UdpConnection>(
839
        [this](
2,434✔
840
            MavlinkReceiver::ParseResult result,
841
            mavlink_message_t& message,
842
            Connection* connection) { receive_message(result, message, connection); },
2,434✔
843
        [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
2,424✔
844
            receive_libmav_message(message, connection);
2,424✔
845
        },
2,431✔
846
        *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
847
        udp.mode == CliArg::Udp::Mode::In ? udp.host : "0.0.0.0",
268✔
848
        udp.mode == CliArg::Udp::Mode::In ? udp.port : 0,
134✔
849
        forwarding_option);
134✔
850

851
    if (!new_conn) {
134✔
852
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
853
    }
854

855
    ConnectionResult ret = new_conn->start();
134✔
856

857
    if (ret != ConnectionResult::Success) {
134✔
858
        return {ret, Mavsdk::ConnectionHandle{}};
×
859
    }
860

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

866
        if (!remote_ip) {
67✔
867
            return {ConnectionResult::DestinationIpUnknown, Mavsdk::ConnectionHandle{}};
×
868
        }
869

870
        new_conn->add_remote_to_keep(remote_ip.value(), udp.port);
67✔
871
        std::lock_guard lock(_mutex);
67✔
872

873
        // With a UDP remote, we need to initiate the connection by sending heartbeats.
874
        auto new_configuration = get_configuration();
67✔
875
        new_configuration.set_always_send_heartbeats(true);
67✔
876
        set_configuration(new_configuration);
67✔
877
    }
67✔
878

879
    auto handle = add_connection(std::move(new_conn));
134✔
880

881
    return {ConnectionResult::Success, handle};
134✔
882
}
134✔
883

884
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
885
MavsdkImpl::add_tcp_connection(const CliArg::Tcp& tcp, ForwardingOption forwarding_option)
8✔
886
{
887
    if (tcp.mode == CliArg::Tcp::Mode::Out) {
8✔
888
        auto new_conn = std::make_unique<TcpClientConnection>(
889
            [this](
37✔
890
                MavlinkReceiver::ParseResult result,
891
                mavlink_message_t& message,
892
                Connection* connection) { receive_message(result, message, connection); },
37✔
893
            [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
37✔
894
                receive_libmav_message(message, connection);
37✔
895
            },
37✔
896
            *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
897
            tcp.host,
4✔
898
            tcp.port,
4✔
899
            forwarding_option);
4✔
900
        if (!new_conn) {
4✔
901
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
902
        }
903
        ConnectionResult ret = new_conn->start();
4✔
904
        if (ret == ConnectionResult::Success) {
4✔
905
            return {ret, add_connection(std::move(new_conn))};
4✔
906
        } else {
907
            return {ret, Mavsdk::ConnectionHandle{}};
×
908
        }
909
    } else {
4✔
910
        auto new_conn = std::make_unique<TcpServerConnection>(
911
            [this](
32✔
912
                MavlinkReceiver::ParseResult result,
913
                mavlink_message_t& message,
914
                Connection* connection) { receive_message(result, message, connection); },
32✔
915
            [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
32✔
916
                receive_libmav_message(message, connection);
32✔
917
            },
32✔
918
            *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
919
            tcp.host,
4✔
920
            tcp.port,
4✔
921
            forwarding_option);
4✔
922
        if (!new_conn) {
4✔
923
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
924
        }
925
        ConnectionResult ret = new_conn->start();
4✔
926
        if (ret == ConnectionResult::Success) {
4✔
927
            return {ret, add_connection(std::move(new_conn))};
4✔
928
        } else {
929
            return {ret, Mavsdk::ConnectionHandle{}};
×
930
        }
931
    }
4✔
932
}
933

934
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
935
    const std::string& dev_path,
936
    int baudrate,
937
    bool flow_control,
938
    ForwardingOption forwarding_option)
939
{
940
    auto new_conn = std::make_unique<SerialConnection>(
941
        [this](
×
942
            MavlinkReceiver::ParseResult result,
943
            mavlink_message_t& message,
944
            Connection* connection) { receive_message(result, message, connection); },
×
945
        [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
×
946
            receive_libmav_message(message, connection);
×
947
        },
×
948
        *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
949
        dev_path,
950
        baudrate,
951
        flow_control,
952
        forwarding_option);
×
953
    if (!new_conn) {
×
954
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
955
    }
956
    ConnectionResult ret = new_conn->start();
×
957
    if (ret == ConnectionResult::Success) {
×
958
        auto handle = add_connection(std::move(new_conn));
×
959

960
        auto new_configuration = get_configuration();
×
961

962
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
963
        // to initiate the MAVLink connection by sending heartbeats.
964
        // Therefore, we override the default here and enable sending heartbeats.
965
        new_configuration.set_always_send_heartbeats(true);
×
966
        set_configuration(new_configuration);
×
967

968
        return {ret, handle};
×
969

970
    } else {
971
        return {ret, Mavsdk::ConnectionHandle{}};
×
972
    }
973
}
×
974

975
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
976
MavsdkImpl::add_raw_connection(ForwardingOption forwarding_option)
2✔
977
{
978
    // Check if a raw connection already exists
979
    if (find_raw_connection() != nullptr) {
2✔
980
        LogErr() << "Raw connection already exists. Only one raw connection is allowed.";
×
981
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
982
    }
983

984
    auto new_conn = std::make_unique<RawConnection>(
985
        [this](
1✔
986
            MavlinkReceiver::ParseResult result,
987
            mavlink_message_t& message,
988
            Connection* connection) { receive_message(result, message, connection); },
1✔
989
        [this](const Mavsdk::MavlinkMessage& message, Connection* connection) {
1✔
990
            receive_libmav_message(message, connection);
1✔
991
        },
1✔
992
        *this,
993
        forwarding_option);
2✔
994

995
    if (!new_conn) {
2✔
996
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
997
    }
998

999
    ConnectionResult ret = new_conn->start();
2✔
1000
    if (ret != ConnectionResult::Success) {
2✔
1001
        return {ret, Mavsdk::ConnectionHandle{}};
×
1002
    }
1003

1004
    auto handle = add_connection(std::move(new_conn));
2✔
1005

1006
    // Enable heartbeats for raw connection
1007
    auto new_configuration = get_configuration();
2✔
1008
    new_configuration.set_always_send_heartbeats(true);
2✔
1009
    set_configuration(new_configuration);
2✔
1010

1011
    return {ConnectionResult::Success, handle};
2✔
1012
}
2✔
1013

1014
Mavsdk::ConnectionHandle MavsdkImpl::add_connection(std::unique_ptr<Connection>&& new_connection)
144✔
1015
{
1016
    std::lock_guard lock(_mutex);
144✔
1017
    auto handle = _connections_handle_factory.create();
144✔
1018
    _connections.emplace_back(ConnectionEntry{std::move(new_connection), handle});
144✔
1019

1020
    return handle;
288✔
1021
}
144✔
1022

1023
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
12✔
1024
{
1025
    std::lock_guard lock(_mutex);
12✔
1026

1027
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
12✔
1028
        return (entry.handle == handle);
12✔
1029
    }));
1030
}
12✔
1031

1032
Mavsdk::Configuration MavsdkImpl::get_configuration() const
69✔
1033
{
1034
    std::lock_guard configuration_lock(_mutex);
69✔
1035
    return _configuration;
138✔
1036
}
69✔
1037

1038
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
207✔
1039
{
1040
    std::lock_guard server_components_lock(_server_components_mutex);
207✔
1041
    // We just point the default to the newly created component. This means
1042
    // that the previous default component will be deleted if it is not
1043
    // used/referenced anywhere.
1044
    _default_server_component = server_component_by_id_with_lock(
414✔
1045
        new_configuration.get_component_id(), new_configuration.get_mav_type());
414✔
1046

1047
    if (new_configuration.get_always_send_heartbeats() &&
345✔
1048
        !_configuration.get_always_send_heartbeats()) {
138✔
1049
        start_sending_heartbeats();
73✔
1050
    } else if (
134✔
1051
        !new_configuration.get_always_send_heartbeats() &&
203✔
1052
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
203✔
1053
        stop_sending_heartbeats();
×
1054
    }
1055

1056
    _configuration = new_configuration;
207✔
1057
    // We cache these values as atomic to avoid having to lock any mutex for them.
1058
    _our_system_id = new_configuration.get_system_id();
207✔
1059
    _our_component_id = new_configuration.get_component_id();
207✔
1060
}
207✔
1061

1062
uint8_t MavsdkImpl::get_own_system_id() const
5,926✔
1063
{
1064
    return _our_system_id;
5,926✔
1065
}
1066

1067
uint8_t MavsdkImpl::get_own_component_id() const
1,454✔
1068
{
1069
    return _our_component_id;
1,454✔
1070
}
1071

1072
uint8_t MavsdkImpl::get_mav_type() const
×
1073
{
UNCOV
1074
    return _configuration.get_mav_type();
×
1075
}
1076

1077
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
142✔
1078
{
1079
    // Needs _systems_lock
1080

1081
    if (_should_exit) {
142✔
1082
        // When the system got destroyed in the destructor, we have to give up.
1083
        return;
×
1084
    }
1085

1086
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
142✔
1087
        LogDebug() << "Initializing connection to remote system...";
×
1088
    } else {
1089
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
284✔
1090
                   << " Comp ID: " << static_cast<int>(comp_id);
142✔
1091
    }
1092

1093
    // Make a system with its first component
1094
    auto new_system = std::make_shared<System>(*this);
142✔
1095
    new_system->init(system_id, comp_id);
142✔
1096

1097
    _systems.emplace_back(system_id, new_system);
142✔
1098
}
142✔
1099

1100
void MavsdkImpl::notify_on_discover()
146✔
1101
{
1102
    // Queue the callbacks without holding the mutex to avoid deadlocks
1103
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
211✔
1104
}
146✔
1105

1106
void MavsdkImpl::notify_on_timeout()
5✔
1107
{
1108
    // Queue the callbacks without holding the mutex to avoid deadlocks
1109
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
5✔
1110
}
5✔
1111

1112
Mavsdk::NewSystemHandle
1113
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
64✔
1114
{
1115
    std::lock_guard lock(_mutex);
64✔
1116

1117
    const auto handle = _new_system_callbacks.subscribe(callback);
64✔
1118

1119
    if (is_any_system_connected()) {
64✔
1120
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
1121
    }
1122

1123
    return handle;
128✔
1124
}
64✔
1125

1126
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
63✔
1127
{
1128
    _new_system_callbacks.unsubscribe(handle);
63✔
1129
}
63✔
1130

1131
bool MavsdkImpl::is_any_system_connected() const
64✔
1132
{
1133
    std::vector<std::shared_ptr<System>> connected_systems = systems();
64✔
1134
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
64✔
1135
        return system->is_connected();
×
1136
    });
64✔
1137
}
64✔
1138

1139
void MavsdkImpl::work_thread()
138✔
1140
{
1141
    while (!_should_exit) {
31,845✔
1142
        // Process incoming messages
1143
        process_messages();
30,938✔
1144

1145
        // Process incoming libmav messages
1146
        process_libmav_messages();
31,255✔
1147

1148
        // Run timers
1149
        timeout_handler.run_once();
31,030✔
1150
        call_every_handler.run_once();
31,721✔
1151

1152
        // Do component work
1153
        {
1154
            std::lock_guard lock(_server_components_mutex);
31,788✔
1155
            for (auto& it : _server_components) {
63,426✔
1156
                if (it.second != nullptr) {
32,006✔
1157
                    it.second->_impl->do_work();
31,660✔
1158
                }
1159
            }
1160
        }
30,918✔
1161

1162
        // Deliver outgoing messages
1163
        deliver_messages();
31,250✔
1164

1165
        // If no messages to send, check if there are messages to receive
1166
        std::unique_lock lock_received(_received_messages_mutex);
31,300✔
1167
        if (_received_messages.empty()) {
31,396✔
1168
            // No messages to process, wait for a signal or timeout
1169
            _received_messages_cv.wait_for(lock_received, std::chrono::milliseconds(10), [this]() {
31,050✔
1170
                return !_received_messages.empty() || _should_exit;
62,909✔
1171
            });
1172
        }
1173
    }
31,949✔
1174
}
301✔
1175

1176
void MavsdkImpl::call_user_callback_located(
1,215✔
1177
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1178
{
1179
    // Don't enqueue callbacks if we're shutting down
1180
    if (_should_exit) {
1,215✔
1181
        return;
×
1182
    }
1183

1184
    auto callback_size = _user_callback_queue.size();
1,214✔
1185

1186
    if (_callback_tracker) {
1,215✔
1187
        _callback_tracker->record_queued(filename, linenumber);
×
1188
        _callback_tracker->maybe_print_stats(callback_size);
×
1189
    }
1190

1191
    if (callback_size >= 100) {
1,215✔
1192
        return;
×
1193

1194
    } else if (callback_size == 99) {
1,215✔
1195
        LogErr()
×
1196
            << "User callback queue overflown\n"
1197
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1198
        return;
×
1199

1200
    } else if (callback_size >= 10) {
1,215✔
1201
        LogWarn()
×
1202
            << "User callback queue slow (queue size: " << callback_size
×
1203
            << ").\n"
1204
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1205
    }
1206

1207
    // We only need to keep track of filename and linenumber if we're actually debugging this.
1208
    UserCallback user_callback =
1209
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
2,430✔
1210

1211
    _user_callback_queue.push_back(std::make_shared<UserCallback>(user_callback));
1,215✔
1212
}
1,215✔
1213

1214
void MavsdkImpl::process_user_callbacks_thread()
138✔
1215
{
1216
    while (!_should_exit) {
1,491✔
1217
        UserCallback callback;
1,353✔
1218
        {
1219
            LockedQueue<UserCallback>::Guard guard(_user_callback_queue);
1,353✔
1220
            auto ptr = guard.wait_and_pop_front();
1,353✔
1221
            if (!ptr) {
1,353✔
1222
                continue;
138✔
1223
            }
1224
            // We need to get a copy instead of just a shared_ptr because the queue might
1225
            // be invalidated when the lock is released.
1226
            callback = *ptr;
1,215✔
1227
        }
1,491✔
1228

1229
        // Check if we're in the process of shutting down before executing the callback
1230
        if (_should_exit) {
1,215✔
1231
            continue;
×
1232
        }
1233

1234
        const double timeout_s = 1.0;
1,215✔
1235
        auto cookie = timeout_handler.add(
1,215✔
1236
            [&]() {
×
1237
                if (_callback_debugging) {
×
1238
                    LogWarn() << "Callback called from " << callback.filename << ":"
×
1239
                              << callback.linenumber << " took more than " << timeout_s
×
1240
                              << " second to run.";
×
1241
                    fflush(stdout);
×
1242
                    fflush(stderr);
×
1243
                    abort();
×
1244
                } else {
1245
                    LogWarn()
×
1246
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
1247
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1248
                }
1249
            },
×
1250
            timeout_s);
1251
        auto callback_start = std::chrono::steady_clock::now();
1,215✔
1252
        callback.func();
1,215✔
1253
        auto callback_end = std::chrono::steady_clock::now();
1,215✔
1254
        timeout_handler.remove(cookie);
1,215✔
1255

1256
        if (_callback_tracker) {
1,215✔
1257
            auto callback_duration_us =
1258
                std::chrono::duration_cast<std::chrono::microseconds>(callback_end - callback_start)
×
1259
                    .count();
×
1260
            _callback_tracker->record_executed(
×
1261
                callback.filename, callback.linenumber, callback_duration_us);
1262
        }
1263
    }
1,353✔
1264
}
138✔
1265

1266
void MavsdkImpl::start_sending_heartbeats()
361✔
1267
{
1268
    // Check if we're in the process of shutting down
1269
    if (_should_exit) {
361✔
1270
        return;
×
1271
    }
1272

1273
    // Before sending out first heartbeats we need to make sure we have a
1274
    // default server component.
1275
    default_server_component_impl();
361✔
1276

1277
    {
1278
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
361✔
1279
        call_every_handler.remove(_heartbeat_send_cookie);
361✔
1280
        _heartbeat_send_cookie =
361✔
1281
            call_every_handler.add([this]() { send_heartbeats(); }, HEARTBEAT_SEND_INTERVAL_S);
811✔
1282
    }
361✔
1283
}
1284

1285
void MavsdkImpl::stop_sending_heartbeats()
5✔
1286
{
1287
    if (!_configuration.get_always_send_heartbeats()) {
5✔
1288
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
1✔
1289
        call_every_handler.remove(_heartbeat_send_cookie);
1✔
1290
    }
1✔
1291
}
5✔
1292

1293
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
1,382✔
1294
{
1295
    std::lock_guard lock(_server_components_mutex);
1,382✔
1296
    return default_server_component_with_lock();
1,381✔
1297
}
1,383✔
1298

1299
ServerComponentImpl& MavsdkImpl::default_server_component_with_lock()
1,383✔
1300
{
1301
    if (_default_server_component == nullptr) {
1,383✔
1302
        _default_server_component =
NEW
1303
            server_component_by_id_with_lock(_our_component_id, get_mav_type());
×
1304
    }
1305
    return *_default_server_component->_impl;
1,381✔
1306
}
1307

1308
void MavsdkImpl::send_heartbeats()
436✔
1309
{
1310
    std::lock_guard lock(_server_components_mutex);
436✔
1311

1312
    for (auto& it : _server_components) {
892✔
1313
        if (it.second != nullptr) {
448✔
1314
            it.second->_impl->send_heartbeat();
448✔
1315
        }
1316
    }
1317
}
443✔
1318

1319
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
24✔
1320
{
1321
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
24✔
1322
    _intercept_incoming_messages_callback = callback;
24✔
1323
}
24✔
1324

1325
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
1326
{
1327
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
14✔
1328
    _intercept_outgoing_messages_callback = callback;
14✔
1329
}
14✔
1330

1331
bool MavsdkImpl::call_json_interception_callbacks(
5,035✔
1332
    const Mavsdk::MavlinkMessage& json_message,
1333
    std::vector<std::pair<Mavsdk::InterceptJsonHandle, Mavsdk::InterceptJsonCallback>>&
1334
        callback_list)
1335
{
1336
    bool keep_message = true;
5,035✔
1337

1338
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
5,035✔
1339
    for (const auto& subscription : callback_list) {
5,024✔
1340
        if (!subscription.second(json_message)) {
2✔
1341
            keep_message = false;
×
1342
        }
1343
    }
1344

1345
    return keep_message;
10,033✔
1346
}
5,011✔
1347

1348
Mavsdk::InterceptJsonHandle
1349
MavsdkImpl::subscribe_incoming_messages_json(const Mavsdk::InterceptJsonCallback& callback)
1✔
1350
{
1351
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1352
    auto handle = _json_handle_factory.create();
1✔
1353
    _incoming_json_message_subscriptions.push_back(std::make_pair(handle, callback));
1✔
1354
    return handle;
2✔
1355
}
1✔
1356

1357
void MavsdkImpl::unsubscribe_incoming_messages_json(Mavsdk::InterceptJsonHandle handle)
1✔
1358
{
1359
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1360
    auto it = std::find_if(
1✔
1361
        _incoming_json_message_subscriptions.begin(),
1362
        _incoming_json_message_subscriptions.end(),
1363
        [handle](const auto& subscription) { return subscription.first == handle; });
1✔
1364
    if (it != _incoming_json_message_subscriptions.end()) {
1✔
1365
        _incoming_json_message_subscriptions.erase(it);
1✔
1366
    }
1367
}
1✔
1368

1369
Mavsdk::InterceptJsonHandle
1370
MavsdkImpl::subscribe_outgoing_messages_json(const Mavsdk::InterceptJsonCallback& callback)
1✔
1371
{
1372
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1373
    auto handle = _json_handle_factory.create();
1✔
1374
    _outgoing_json_message_subscriptions.push_back(std::make_pair(handle, callback));
1✔
1375
    return handle;
2✔
1376
}
1✔
1377

1378
void MavsdkImpl::unsubscribe_outgoing_messages_json(Mavsdk::InterceptJsonHandle handle)
1✔
1379
{
1380
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1381
    auto it = std::find_if(
1✔
1382
        _outgoing_json_message_subscriptions.begin(),
1383
        _outgoing_json_message_subscriptions.end(),
1384
        [handle](const auto& subscription) { return subscription.first == handle; });
1✔
1385
    if (it != _outgoing_json_message_subscriptions.end()) {
1✔
1386
        _outgoing_json_message_subscriptions.erase(it);
1✔
1387
    }
1388
}
1✔
1389

1390
RawConnection* MavsdkImpl::find_raw_connection()
4✔
1391
{
1392
    std::lock_guard lock(_mutex);
4✔
1393

1394
    for (auto& entry : _connections) {
4✔
1395
        auto* raw_conn = dynamic_cast<RawConnection*>(entry.connection.get());
2✔
1396
        if (raw_conn != nullptr) {
2✔
1397
            return raw_conn;
2✔
1398
        }
1399
    }
1400
    return nullptr;
2✔
1401
}
4✔
1402

1403
void MavsdkImpl::pass_received_raw_bytes(const char* bytes, size_t length)
1✔
1404
{
1405
    auto* raw_conn = find_raw_connection();
1✔
1406
    if (raw_conn == nullptr) {
1✔
1407
        LogErr()
×
1408
            << "No raw connection available. Please add one using add_any_connection(\"raw://\")";
×
1409
        return;
×
1410
    }
1411

1412
    raw_conn->receive(bytes, length);
1✔
1413
}
1414

1415
Mavsdk::RawBytesHandle
1416
MavsdkImpl::subscribe_raw_bytes_to_be_sent(const Mavsdk::RawBytesCallback& callback)
1✔
1417
{
1418
    if (find_raw_connection() == nullptr) {
1✔
1419
        LogWarn() << "No raw connection available. Subscription will only receive bytes after you "
×
1420
                     "add a connection using add_any_connection(\"raw://\")";
×
1421
    }
1422
    return _raw_bytes_subscriptions.subscribe(callback);
1✔
1423
}
1424

1425
void MavsdkImpl::unsubscribe_raw_bytes_to_be_sent(Mavsdk::RawBytesHandle handle)
1✔
1426
{
1427
    _raw_bytes_subscriptions.unsubscribe(handle);
1✔
1428
}
1✔
1429

1430
bool MavsdkImpl::notify_raw_bytes_sent(const char* bytes, size_t length)
3✔
1431
{
1432
    if (_raw_bytes_subscriptions.empty()) {
3✔
1433
        return false;
2✔
1434
    }
1435

1436
    _raw_bytes_subscriptions(bytes, length);
1✔
1437

1438
    return true;
1✔
1439
}
1440

1441
Mavsdk::ConnectionErrorHandle
1442
MavsdkImpl::subscribe_connection_errors(Mavsdk::ConnectionErrorCallback callback)
×
1443
{
1444
    std::lock_guard lock(_mutex);
×
1445

1446
    const auto handle = _connections_errors_subscriptions.subscribe(callback);
×
1447

1448
    return handle;
×
1449
}
×
1450

1451
void MavsdkImpl::unsubscribe_connection_errors(Mavsdk::ConnectionErrorHandle handle)
×
1452
{
1453
    std::lock_guard lock(_mutex);
×
1454
    _connections_errors_subscriptions.unsubscribe(handle);
×
1455
}
×
1456

1457
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
2,536✔
1458
{
1459
    // Checks whether connection knows target system ID by extracting target system if set.
1460
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
2,536✔
1461

1462
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
2,530✔
1463
        return 0;
660✔
1464
    }
1465

1466
    // Don't look at the target system offset if it is outside the payload length.
1467
    // This can happen if the fields are trimmed.
1468
    if (meta->target_system_ofs >= message.len) {
1,870✔
1469
        return 0;
24✔
1470
    }
1471

1472
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,846✔
1473
}
1474

1475
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
51✔
1476
{
1477
    // Checks whether connection knows target system ID by extracting target system if set.
1478
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
51✔
1479

1480
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
51✔
1481
        return 0;
34✔
1482
    }
1483

1484
    // Don't look at the target component offset if it is outside the payload length.
1485
    // This can happen if the fields are trimmed.
1486
    if (meta->target_component_ofs >= message.len) {
17✔
1487
        return 0;
1✔
1488
    }
1489

1490
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
16✔
1491
}
1492

1493
Sender& MavsdkImpl::sender()
×
1494
{
1495
    std::lock_guard lock(_server_components_mutex);
×
1496
    return default_server_component_with_lock().sender();
×
1497
}
×
1498

1499
std::vector<Connection*> MavsdkImpl::get_connections() const
2,541✔
1500
{
1501
    std::lock_guard lock(_mutex);
2,541✔
1502
    std::vector<Connection*> connections;
2,549✔
1503
    for (const auto& connection_entry : _connections) {
5,030✔
1504
        connections.push_back(connection_entry.connection.get());
2,488✔
1505
    }
1506
    return connections;
2,544✔
1507
}
2,544✔
1508

1509
mav::MessageSet& MavsdkImpl::get_message_set() const
23✔
1510
{
1511
    // Note: This returns a reference to MessageSet without locking.
1512
    // Thread safety for MessageSet operations must be ensured by:
1513
    // 1. Using load_custom_xml_to_message_set() for write operations (XML loading)
1514
    // 2. libmav MessageSet should be internally thread-safe for read operations
1515
    // 3. If race conditions persist, consider implementing a thread-safe MessageSet wrapper
1516
    return *_message_set;
23✔
1517
}
1518

1519
bool MavsdkImpl::load_custom_xml_to_message_set(const std::string& xml_content)
6✔
1520
{
1521
    std::lock_guard<std::mutex> lock(_message_set_mutex);
6✔
1522
    auto result = _message_set->addFromXMLString(xml_content, false /* recursive_open_includes */);
6✔
1523
    return result == ::mav::MessageSetResult::Success;
12✔
1524
}
6✔
1525

1526
// Thread-safe MessageSet read operations
1527
std::optional<std::string> MavsdkImpl::message_id_to_name_safe(uint32_t id) const
×
1528
{
1529
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1530
    auto message_def = _message_set->getMessageDefinition(static_cast<int>(id));
×
1531
    if (message_def) {
×
1532
        return message_def.get().name();
×
1533
    }
1534
    return std::nullopt;
×
1535
}
×
1536

1537
std::optional<int> MavsdkImpl::message_name_to_id_safe(const std::string& name) const
×
1538
{
1539
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1540
    return _message_set->idForMessage(name);
×
1541
}
×
1542

1543
std::optional<mav::Message> MavsdkImpl::create_message_safe(const std::string& message_name) const
×
1544
{
1545
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1546
    return _message_set->create(message_name);
×
1547
}
×
1548

1549
// Thread-safe parsing for LibmavReceiver
1550
std::optional<mav::Message> MavsdkImpl::parse_message_safe(
5,039✔
1551
    const uint8_t* buffer, size_t buffer_len, size_t& bytes_consumed) const
1552
{
1553
    std::lock_guard<std::mutex> lock(_message_set_mutex);
5,039✔
1554
    return _buffer_parser->parseMessage(buffer, buffer_len, bytes_consumed);
5,050✔
1555
}
5,046✔
1556

1557
mav::OptionalReference<const mav::MessageDefinition>
1558
MavsdkImpl::get_message_definition_safe(int message_id) const
4,968✔
1559
{
1560
    std::lock_guard<std::mutex> lock(_message_set_mutex);
4,968✔
1561
    return _message_set->getMessageDefinition(message_id);
4,964✔
1562
}
4,969✔
1563

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