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

mavlink / MAVSDK / 17823325850

18 Sep 2025 08:49AM UTC coverage: 47.633% (+0.008%) from 47.625%
17823325850

push

github

web-flow
Merge pull request #2655 from mavlink/pr-mavlink-direct-docs

Add MavlinkDirect docs and more examples

17044 of 35782 relevant lines covered (47.63%)

451.46 hits per line

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

70.22
/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) :
122✔
29
    timeout_handler(time),
122✔
30
    call_every_handler(time)
244✔
31
{
32
    LogInfo() << "MAVSDK version: " << mavsdk_version;
122✔
33

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

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

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

55
    set_configuration(configuration);
122✔
56

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

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

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

71
    _process_user_callbacks_thread =
244✔
72
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
122✔
73

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

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

84
    _should_exit = true;
122✔
85

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

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

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

102
    std::lock_guard lock(_mutex);
122✔
103

104
    _systems.clear();
122✔
105
    _connections.clear();
122✔
106
}
122✔
107

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

112
    ++version_counter;
1✔
113

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

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

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

151
    return systems_result;
157✔
152
}
157✔
153

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

304
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
123✔
305
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
246✔
306

307
    return _server_components.back().second;
123✔
308
}
309

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

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

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

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

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

351
void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connection)
2,423✔
352
{
353
    {
354
        std::lock_guard lock(_received_messages_mutex);
2,423✔
355
        _received_messages.emplace(ReceivedMessage{std::move(message), connection});
2,427✔
356
    }
2,426✔
357
    _received_messages_cv.notify_one();
2,428✔
358
}
2,429✔
359

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

370
void MavsdkImpl::process_messages()
25,643✔
371
{
372
    std::lock_guard lock(_received_messages_mutex);
25,643✔
373
    while (!_received_messages.empty()) {
27,743✔
374
        auto message_copied = _received_messages.front();
2,408✔
375
        process_message(message_copied.message, message_copied.connection_ptr);
2,409✔
376
        _received_messages.pop();
2,409✔
377
    }
378
}
24,945✔
379

380
void MavsdkImpl::process_libmav_messages()
25,541✔
381
{
382
    std::lock_guard lock(_received_libmav_messages_mutex);
25,541✔
383
    while (!_received_libmav_messages.empty()) {
27,522✔
384
        auto message_copied = _received_libmav_messages.front();
2,401✔
385
        process_libmav_message(message_copied.message, message_copied.connection_ptr);
2,404✔
386
        _received_libmav_messages.pop();
2,404✔
387
    }
2,405✔
388
}
24,192✔
389

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

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

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

404
    {
405
        std::lock_guard lock(_mutex);
2,408✔
406

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

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

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

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

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

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

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

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

477
        bool found_system = false;
2,371✔
478
        for (auto& system : _systems) {
2,407✔
479
            if (system.first == message.sysid) {
2,288✔
480
                system.second->system_impl()->add_new_component(message.compid);
2,252✔
481
                found_system = true;
2,253✔
482
                break;
2,253✔
483
            }
484
        }
485

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

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

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

511
    mavlink_message_handler.process_message(message);
2,371✔
512

513
    for (auto& system : _systems) {
2,410✔
514
        if (system.first == message.sysid) {
2,411✔
515
            system.second->system_impl()->process_mavlink_message(message);
2,373✔
516
            break;
2,374✔
517
        }
518
    }
519
}
520

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

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

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

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

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

553
    {
554
        std::lock_guard lock(_mutex);
2,402✔
555

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

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

573
        bool found_system = false;
2,401✔
574
        for (auto& system : _systems) {
2,436✔
575
            if (system.first == message.system_id) {
2,434✔
576
                system.second->system_impl()->add_new_component(message.component_id);
2,399✔
577
                found_system = true;
2,398✔
578
                break;
2,398✔
579
            }
580
        }
581

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

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

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

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

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

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

625
    {
626
        std::lock_guard lock(_messages_to_send_mutex);
2,530✔
627
        _messages_to_send.push(std::move(message_copy));
2,529✔
628
    }
2,529✔
629

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

637
    return true;
2,529✔
638
}
639

640
void MavsdkImpl::deliver_messages()
28,135✔
641
{
642
    // Process messages one at a time to avoid holding the mutex while delivering
643
    while (true) {
644
        mavlink_message_t message;
645
        {
646
            std::lock_guard lock(_messages_to_send_mutex);
28,135✔
647
            if (_messages_to_send.empty()) {
27,566✔
648
                break;
25,051✔
649
            }
650
            message = _messages_to_send.front();
2,528✔
651
            _messages_to_send.pop();
2,528✔
652
        }
27,580✔
653
        deliver_message(message);
2,528✔
654
    }
2,530✔
655
}
24,941✔
656

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

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

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

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

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

692
    if (libmav_msg_opt) {
2,442✔
693
        // Create Mavsdk::MavlinkMessage directly for JSON interception
694
        Mavsdk::MavlinkMessage json_message;
2,443✔
695
        json_message.message_name = libmav_msg_opt.value().name();
2,439✔
696
        json_message.system_id = message.sysid;
2,441✔
697
        json_message.component_id = message.compid;
2,441✔
698

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

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

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

738
    std::lock_guard lock(_mutex);
2,439✔
739

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

746
    uint8_t successful_emissions = 0;
2,379✔
747
    for (auto& _connection : _connections) {
4,782✔
748
        const uint8_t target_system_id = get_target_system_id(message);
2,404✔
749

750
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
2,401✔
751
            continue;
9✔
752
        }
753
        const auto result = (*_connection.connection).send_message(message);
2,391✔
754
        if (result.first) {
2,396✔
755
            successful_emissions++;
2,394✔
756
        } else {
757
            _connections_errors_subscriptions.queue(
4✔
758
                Mavsdk::ConnectionError{result.second, _connection.handle},
2✔
759
                [this](const auto& func) { call_user_callback(func); });
×
760
        }
761
    }
2,396✔
762

763
    if (successful_emissions == 0) {
2,381✔
764
        LogErr() << "Sending message failed";
×
765
    }
766
}
2,442✔
767

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

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

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

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

815
    ConnectionResult ret = new_conn->start();
122✔
816

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

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

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

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

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

839
    auto handle = add_connection(std::move(new_conn));
122✔
840

841
    return {ConnectionResult::Success, handle};
122✔
842
}
122✔
843

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

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

917
        auto new_configuration = get_configuration();
×
918

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

925
        return {ret, handle};
×
926

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

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

938
    return handle;
248✔
939
}
124✔
940

941
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
×
942
{
943
    std::lock_guard lock(_mutex);
×
944

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

950
Mavsdk::Configuration MavsdkImpl::get_configuration() const
61✔
951
{
952
    std::lock_guard configuration_lock(_mutex);
61✔
953
    return _configuration;
122✔
954
}
61✔
955

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

965
    if (new_configuration.get_always_send_heartbeats() &&
305✔
966
        !_configuration.get_always_send_heartbeats()) {
122✔
967
        start_sending_heartbeats();
62✔
968
    } else if (
121✔
969
        !new_configuration.get_always_send_heartbeats() &&
182✔
970
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
182✔
971
        stop_sending_heartbeats();
×
972
    }
973

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

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

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

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

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

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

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

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

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

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

1028
    _systems.emplace_back(system_id, new_system);
127✔
1029
}
127✔
1030

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

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

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

1048
    const auto handle = _new_system_callbacks.subscribe(callback);
57✔
1049

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

1054
    return handle;
114✔
1055
}
57✔
1056

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

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

1070
void MavsdkImpl::work_thread()
122✔
1071
{
1072
    while (!_should_exit) {
25,475✔
1073
        // Process incoming messages
1074
        process_messages();
24,803✔
1075

1076
        // Process incoming libmav messages
1077
        process_libmav_messages();
24,660✔
1078

1079
        // Run timers
1080
        timeout_handler.run_once();
24,737✔
1081
        call_every_handler.run_once();
25,274✔
1082

1083
        // Do component work
1084
        {
1085
            std::lock_guard lock(_server_components_mutex);
25,561✔
1086
            for (auto& it : _server_components) {
50,700✔
1087
                if (it.second != nullptr) {
25,661✔
1088
                    it.second->_impl->do_work();
25,575✔
1089
                }
1090
            }
1091
        }
24,695✔
1092

1093
        // Deliver outgoing messages
1094
        deliver_messages();
24,934✔
1095

1096
        // If no messages to send, check if there are messages to receive
1097
        std::unique_lock lock_received(_received_messages_mutex);
25,028✔
1098
        if (_received_messages.empty()) {
25,131✔
1099
            // No messages to process, wait for a signal or timeout
1100
            _received_messages_cv.wait_for(lock_received, std::chrono::milliseconds(10), [this]() {
24,735✔
1101
                return !_received_messages.empty() || _should_exit;
50,548✔
1102
            });
1103
        }
1104
    }
25,545✔
1105
}
240✔
1106

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

1115
    auto callback_size = _user_callback_queue.size();
1,193✔
1116
    if (callback_size == 10) {
1,193✔
1117
        LogWarn()
×
1118
            << "User callback queue too slow.\n"
1119
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1120

1121
    } else if (callback_size == 99) {
1,193✔
1122
        LogErr()
×
1123
            << "User callback queue overflown\n"
1124
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1125

1126
    } else if (callback_size == 100) {
1,193✔
1127
        return;
×
1128
    }
1129

1130
    // We only need to keep track of filename and linenumber if we're actually debugging this.
1131
    UserCallback user_callback =
1132
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
2,386✔
1133

1134
    _user_callback_queue.push_back(std::make_shared<UserCallback>(user_callback));
1,193✔
1135
}
1,193✔
1136

1137
void MavsdkImpl::process_user_callbacks_thread()
122✔
1138
{
1139
    while (!_should_exit) {
1,437✔
1140
        UserCallback callback;
1,315✔
1141
        {
1142
            LockedQueue<UserCallback>::Guard guard(_user_callback_queue);
1,315✔
1143
            auto ptr = guard.wait_and_pop_front();
1,315✔
1144
            if (!ptr) {
1,315✔
1145
                continue;
122✔
1146
            }
1147
            // We need to get a copy instead of just a shared_ptr because the queue might
1148
            // be invalidated when the lock is released.
1149
            callback = *ptr;
1,193✔
1150
        }
1,437✔
1151

1152
        // Check if we're in the process of shutting down before executing the callback
1153
        if (_should_exit) {
1,193✔
1154
            continue;
×
1155
        }
1156

1157
        const double timeout_s = 1.0;
1,193✔
1158
        auto cookie = timeout_handler.add(
1,193✔
1159
            [&]() {
×
1160
                if (_callback_debugging) {
×
1161
                    LogWarn() << "Callback called from " << callback.filename << ":"
×
1162
                              << callback.linenumber << " took more than " << timeout_s
×
1163
                              << " second to run.";
×
1164
                    fflush(stdout);
×
1165
                    fflush(stderr);
×
1166
                    abort();
×
1167
                } else {
1168
                    LogWarn()
×
1169
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
1170
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1171
                }
1172
            },
×
1173
            timeout_s);
1174
        callback.func();
1,193✔
1175
        timeout_handler.remove(cookie);
1,193✔
1176
    }
1,315✔
1177
}
122✔
1178

1179
void MavsdkImpl::start_sending_heartbeats()
316✔
1180
{
1181
    // Check if we're in the process of shutting down
1182
    if (_should_exit) {
316✔
1183
        return;
×
1184
    }
1185

1186
    // Before sending out first heartbeats we need to make sure we have a
1187
    // default server component.
1188
    default_server_component_impl();
315✔
1189

1190
    {
1191
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
316✔
1192
        call_every_handler.remove(_heartbeat_send_cookie);
316✔
1193
        _heartbeat_send_cookie =
315✔
1194
            call_every_handler.add([this]() { send_heartbeats(); }, HEARTBEAT_SEND_INTERVAL_S);
680✔
1195
    }
315✔
1196
}
1197

1198
void MavsdkImpl::stop_sending_heartbeats()
×
1199
{
1200
    if (!_configuration.get_always_send_heartbeats()) {
×
1201
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
×
1202
        call_every_handler.remove(_heartbeat_send_cookie);
×
1203
    }
×
1204
}
×
1205

1206
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
1,311✔
1207
{
1208
    std::lock_guard lock(_server_components_mutex);
1,311✔
1209
    return default_server_component_with_lock();
1,311✔
1210
}
1,310✔
1211

1212
ServerComponentImpl& MavsdkImpl::default_server_component_with_lock()
1,311✔
1213
{
1214
    if (_default_server_component == nullptr) {
1,311✔
1215
        _default_server_component = server_component_by_id_with_lock(_our_component_id);
×
1216
    }
1217
    return *_default_server_component->_impl;
1,311✔
1218
}
1219

1220
void MavsdkImpl::send_heartbeats()
362✔
1221
{
1222
    std::lock_guard lock(_server_components_mutex);
362✔
1223

1224
    for (auto& it : _server_components) {
721✔
1225
        if (it.second != nullptr) {
365✔
1226
            it.second->_impl->send_heartbeat();
364✔
1227
        }
1228
    }
1229
}
359✔
1230

1231
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
24✔
1232
{
1233
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
24✔
1234
    _intercept_incoming_messages_callback = callback;
24✔
1235
}
24✔
1236

1237
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
1238
{
1239
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
14✔
1240
    _intercept_outgoing_messages_callback = callback;
14✔
1241
}
14✔
1242

1243
bool MavsdkImpl::call_json_interception_callbacks(
4,847✔
1244
    const Mavsdk::MavlinkMessage& json_message,
1245
    std::vector<std::pair<Mavsdk::InterceptJsonHandle, Mavsdk::InterceptJsonCallback>>&
1246
        callback_list)
1247
{
1248
    bool keep_message = true;
4,847✔
1249

1250
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
4,847✔
1251
    for (const auto& subscription : callback_list) {
4,847✔
1252
        if (!subscription.second(json_message)) {
2✔
1253
            keep_message = false;
×
1254
        }
1255
    }
1256

1257
    return keep_message;
9,687✔
1258
}
4,842✔
1259

1260
Mavsdk::InterceptJsonHandle
1261
MavsdkImpl::subscribe_incoming_messages_json(const Mavsdk::InterceptJsonCallback& callback)
1✔
1262
{
1263
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1264
    auto handle = _json_handle_factory.create();
1✔
1265
    _incoming_json_message_subscriptions.push_back(std::make_pair(handle, callback));
1✔
1266
    return handle;
2✔
1267
}
1✔
1268

1269
void MavsdkImpl::unsubscribe_incoming_messages_json(Mavsdk::InterceptJsonHandle handle)
1✔
1270
{
1271
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1272
    auto it = std::find_if(
1✔
1273
        _incoming_json_message_subscriptions.begin(),
1274
        _incoming_json_message_subscriptions.end(),
1275
        [handle](const auto& subscription) { return subscription.first == handle; });
1✔
1276
    if (it != _incoming_json_message_subscriptions.end()) {
1✔
1277
        _incoming_json_message_subscriptions.erase(it);
1✔
1278
    }
1279
}
1✔
1280

1281
Mavsdk::InterceptJsonHandle
1282
MavsdkImpl::subscribe_outgoing_messages_json(const Mavsdk::InterceptJsonCallback& callback)
1✔
1283
{
1284
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
1✔
1285
    auto handle = _json_handle_factory.create();
1✔
1286
    _outgoing_json_message_subscriptions.push_back(std::make_pair(handle, callback));
1✔
1287
    return handle;
2✔
1288
}
1✔
1289

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

1302
Mavsdk::ConnectionErrorHandle
1303
MavsdkImpl::subscribe_connection_errors(Mavsdk::ConnectionErrorCallback callback)
×
1304
{
1305
    std::lock_guard lock(_mutex);
×
1306

1307
    const auto handle = _connections_errors_subscriptions.subscribe(callback);
×
1308

1309
    return handle;
×
1310
}
×
1311

1312
void MavsdkImpl::unsubscribe_connection_errors(Mavsdk::ConnectionErrorHandle handle)
×
1313
{
1314
    std::lock_guard lock(_mutex);
×
1315
    _connections_errors_subscriptions.unsubscribe(handle);
×
1316
}
×
1317

1318
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
2,457✔
1319
{
1320
    // Checks whether connection knows target system ID by extracting target system if set.
1321
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
2,457✔
1322

1323
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
2,457✔
1324
        return 0;
575✔
1325
    }
1326

1327
    // Don't look at the target system offset if it is outside the payload length.
1328
    // This can happen if the fields are trimmed.
1329
    if (meta->target_system_ofs >= message.len) {
1,882✔
1330
        return 0;
21✔
1331
    }
1332

1333
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,861✔
1334
}
1335

1336
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
53✔
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);
53✔
1340

1341
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
53✔
1342
        return 0;
28✔
1343
    }
1344

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

1351
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
23✔
1352
}
1353

1354
Sender& MavsdkImpl::sender()
×
1355
{
1356
    std::lock_guard lock(_server_components_mutex);
×
1357
    return default_server_component_with_lock().sender();
×
1358
}
×
1359

1360
std::vector<Connection*> MavsdkImpl::get_connections() const
2,440✔
1361
{
1362
    std::lock_guard lock(_mutex);
2,440✔
1363
    std::vector<Connection*> connections;
2,439✔
1364
    for (const auto& connection_entry : _connections) {
4,841✔
1365
        connections.push_back(connection_entry.connection.get());
2,405✔
1366
    }
1367
    return connections;
2,440✔
1368
}
2,440✔
1369

1370
mav::MessageSet& MavsdkImpl::get_message_set() const
22✔
1371
{
1372
    // Note: This returns a reference to MessageSet without locking.
1373
    // Thread safety for MessageSet operations must be ensured by:
1374
    // 1. Using load_custom_xml_to_message_set() for write operations (XML loading)
1375
    // 2. libmav MessageSet should be internally thread-safe for read operations
1376
    // 3. If race conditions persist, consider implementing a thread-safe MessageSet wrapper
1377
    return *_message_set;
22✔
1378
}
1379

1380
bool MavsdkImpl::load_custom_xml_to_message_set(const std::string& xml_content)
6✔
1381
{
1382
    std::lock_guard<std::mutex> lock(_message_set_mutex);
6✔
1383
    auto result = _message_set->addFromXMLString(xml_content, false /* recursive_open_includes */);
6✔
1384
    return result == ::mav::MessageSetResult::Success;
12✔
1385
}
6✔
1386

1387
// Thread-safe MessageSet read operations
1388
std::optional<std::string> MavsdkImpl::message_id_to_name_safe(uint32_t id) const
×
1389
{
1390
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1391
    auto message_def = _message_set->getMessageDefinition(static_cast<int>(id));
×
1392
    if (message_def) {
×
1393
        return message_def.get().name();
×
1394
    }
1395
    return std::nullopt;
×
1396
}
×
1397

1398
std::optional<int> MavsdkImpl::message_name_to_id_safe(const std::string& name) const
×
1399
{
1400
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1401
    return _message_set->idForMessage(name);
×
1402
}
×
1403

1404
std::optional<mav::Message> MavsdkImpl::create_message_safe(const std::string& message_name) const
×
1405
{
1406
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
1407
    return _message_set->create(message_name);
×
1408
}
×
1409

1410
// Thread-safe parsing for LibmavReceiver
1411
std::optional<mav::Message> MavsdkImpl::parse_message_safe(
4,865✔
1412
    const uint8_t* buffer, size_t buffer_len, size_t& bytes_consumed) const
1413
{
1414
    std::lock_guard<std::mutex> lock(_message_set_mutex);
4,865✔
1415
    return _buffer_parser->parseMessage(buffer, buffer_len, bytes_consumed);
4,866✔
1416
}
4,867✔
1417

1418
mav::OptionalReference<const mav::MessageDefinition>
1419
MavsdkImpl::get_message_definition_safe(int message_id) const
4,799✔
1420
{
1421
    std::lock_guard<std::mutex> lock(_message_set_mutex);
4,799✔
1422
    return _message_set->getMessageDefinition(message_id);
4,805✔
1423
}
4,803✔
1424

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