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

mavlink / MAVSDK / 16952450702

14 Aug 2025 12:15AM UTC coverage: 47.243% (+0.8%) from 46.441%
16952450702

Pull #2638

github

web-flow
Merge c7c88c2bd into 3a9af632b
Pull Request #2638: Add new JSON based interception API

340 of 369 new or added lines in 5 files covered. (92.14%)

13 existing lines in 3 files now uncovered.

16701 of 35351 relevant lines covered (47.24%)

444.08 hits per line

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

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

34
    if (const char* env_p = std::getenv("MAVSDK_CALLBACK_DEBUGGING")) {
114✔
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")) {
114✔
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")) {
114✔
49
        if (std::string(env_p) == "1") {
×
50
            LogDebug() << "System debugging is on.";
×
51
            _system_debugging = true;
×
52
        }
53
    }
54

55
    set_configuration(configuration);
114✔
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>();
114✔
60
    _message_set->addFromXMLString(mav_embedded::MINIMAL_XML);
114✔
61
    _message_set->addFromXMLString(mav_embedded::STANDARD_XML);
114✔
62
    _message_set->addFromXMLString(mav_embedded::COMMON_XML);
114✔
63
    _message_set->addFromXMLString(mav_embedded::ARDUPILOTMEGA_XML);
114✔
64

65
    // Initialize BufferParser for thread-safe parsing
66
    _buffer_parser = std::make_unique<mav::BufferParser>(*_message_set);
114✔
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 =
228✔
72
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
114✔
73

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

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

84
    _should_exit = true;
114✔
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) {
114✔
90
        _work_thread->join();
114✔
91
        delete _work_thread;
114✔
92
        _work_thread = nullptr;
114✔
93
    }
94

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

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

104
    _systems.clear();
114✔
105
    _connections.clear();
114✔
106
}
114✔
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
137✔
137
{
138
    std::vector<std::shared_ptr<System>> systems_result{};
137✔
139

140
    std::lock_guard lock(_mutex);
137✔
141
    for (auto& system : _systems) {
218✔
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) {
81✔
146
            continue;
×
147
        }
148
        systems_result.push_back(system.second);
81✔
149
    }
150

151
    return systems_result;
137✔
152
}
137✔
153

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

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

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

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

185
    if (timeout_s > 0.0) {
43✔
186
        if (fut.wait_for(std::chrono::milliseconds(int64_t(timeout_s * 1e3))) ==
43✔
187
            std::future_status::ready) {
188
            unsubscribe_on_new_system(handle);
43✔
189
            return fut.get();
43✔
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
}
43✔
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)
222✔
293
{
294
    for (auto& it : _server_components) {
223✔
295
        if (it.first == component_id) {
108✔
296
            if (it.second != nullptr) {
107✔
297
                return it.second;
107✔
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>>(
115✔
305
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
230✔
306

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

310
void MavsdkImpl::forward_message(mavlink_message_t& message, Connection* connection)
41✔
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;
41✔
316
    const uint8_t target_system_id = get_target_system_id(message);
41✔
317
    const uint8_t target_component_id = get_target_component_id(message);
41✔
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());
41✔
322

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

327
    if (!targeted_only_at_us && heartbeat_check_ok) {
41✔
328
        unsigned successful_emissions = 0;
36✔
329
        for (auto& entry : _connections) {
108✔
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 ||
108✔
333
                !entry.connection->should_forward_messages()) {
36✔
334
                continue;
36✔
335
            }
336
            auto result = (*entry.connection).send_message(message);
36✔
337
            if (result.first) {
36✔
338
                successful_emissions++;
35✔
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
        }
36✔
345
        if (successful_emissions == 0) {
36✔
346
            LogErr() << "Message forwarding failed";
1✔
347
        }
348
    }
349
}
41✔
350

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

360
void MavsdkImpl::receive_libmav_message(const LibmavMessage& message, Connection* connection)
2,342✔
361
{
362
    {
363
        std::lock_guard lock(_received_libmav_messages_mutex);
2,342✔
364
        _received_libmav_messages.emplace(ReceivedLibmavMessage{message, connection});
2,340✔
365
    }
2,340✔
366
    _received_libmav_messages_cv.notify_one();
2,341✔
367
}
2,343✔
368

369
void MavsdkImpl::process_messages()
23,192✔
370
{
371
    std::lock_guard lock(_received_messages_mutex);
23,192✔
372
    while (!_received_messages.empty()) {
25,431✔
373
        auto message_copied = _received_messages.front();
2,326✔
374
        process_message(message_copied.message, message_copied.connection_ptr);
2,326✔
375
        _received_messages.pop();
2,328✔
376
    }
377
}
22,854✔
378

379
void MavsdkImpl::process_libmav_messages()
23,026✔
380
{
381
    std::lock_guard lock(_received_libmav_messages_mutex);
23,026✔
382
    while (!_received_libmav_messages.empty()) {
25,289✔
383
        auto message_copied = _received_libmav_messages.front();
2,322✔
384
        process_libmav_message(message_copied.message, message_copied.connection_ptr);
2,323✔
385
        _received_libmav_messages.pop();
2,322✔
386
    }
2,325✔
387
}
22,812✔
388

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

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

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

403
    {
404
        std::lock_guard lock(_mutex);
2,328✔
405

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

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

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

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

445
            if (!keep) {
2,325✔
446
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
32✔
447
                return;
32✔
448
            }
449
        }
450

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

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

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

476
        bool found_system = false;
2,296✔
477
        for (auto& system : _systems) {
2,325✔
478
            if (system.first == message.sysid) {
2,212✔
479
                system.second->system_impl()->add_new_component(message.compid);
2,183✔
480
                found_system = true;
2,181✔
481
                break;
2,181✔
482
            }
483
        }
484

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

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

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

510
    mavlink_message_handler.process_message(message);
2,294✔
511

512
    for (auto& system : _systems) {
2,327✔
513
        if (system.first == message.sysid) {
2,327✔
514
            system.second->system_impl()->process_mavlink_message(message);
2,295✔
515
            break;
2,296✔
516
        }
517
    }
518
}
519

520
void MavsdkImpl::process_libmav_message(const LibmavMessage& message, Connection* /* connection */)
2,325✔
521
{
522
    // Assumes _received_libmav_messages_mutex
523

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

530
    // JSON message interception for incoming messages
531
    auto json_message = libmav_to_mavsdk_message(message);
2,325✔
532
    if (!call_json_interception_callbacks(json_message, _incoming_json_message_subscriptions)) {
2,322✔
533
        // Message was dropped by interception callback
NEW
534
        if (_message_logging_on) {
×
NEW
535
            LogDebug() << "Incoming JSON message " << message.message_name
×
NEW
536
                       << " dropped by interception";
×
537
        }
NEW
538
        return;
×
539
    }
540

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

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

552
    {
553
        std::lock_guard lock(_mutex);
2,323✔
554

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

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

572
        bool found_system = false;
2,323✔
573
        for (auto& system : _systems) {
2,355✔
574
            if (system.first == message.system_id) {
2,350✔
575
                system.second->system_impl()->add_new_component(message.component_id);
2,318✔
576
                found_system = true;
2,317✔
577
                break;
2,317✔
578
            }
579
        }
580

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

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

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

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

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

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

624
    {
625
        std::lock_guard lock(_messages_to_send_mutex);
2,447✔
626
        _messages_to_send.push(std::move(message_copy));
2,448✔
627
    }
2,449✔
628

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

636
    return true;
2,450✔
637
}
638

639
void MavsdkImpl::deliver_messages()
25,539✔
640
{
641
    // Process messages one at a time to avoid holding the mutex while delivering
642
    while (true) {
643
        mavlink_message_t message;
644
        {
645
            std::lock_guard lock(_messages_to_send_mutex);
25,539✔
646
            if (_messages_to_send.empty()) {
25,411✔
647
                break;
23,071✔
648
            }
649
            message = _messages_to_send.front();
2,445✔
650
            _messages_to_send.pop();
2,448✔
651
        }
25,519✔
652
        deliver_message(message);
2,448✔
653
    }
2,450✔
654
}
22,930✔
655

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

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

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

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

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

691
    if (libmav_msg_opt) {
2,362✔
692
        // Create LibmavMessage with JSON
693
        LibmavMessage libmav_message;
2,357✔
694
        libmav_message.message = libmav_msg_opt.value();
2,359✔
695
        libmav_message.message_name = libmav_msg_opt.value().name();
2,360✔
696
        libmav_message.system_id = message.sysid;
2,360✔
697
        libmav_message.component_id = message.compid;
2,360✔
698

699
        // Extract target_system and target_component if present
700
        uint8_t target_system = 0;
2,360✔
701
        uint8_t target_component = 0;
2,360✔
702
        if (libmav_msg_opt.value().get("target_system", target_system) ==
2,360✔
703
            mav::MessageResult::Success) {
704
            libmav_message.target_system = target_system;
1,812✔
705
        } else {
706
            libmav_message.target_system = 0;
547✔
707
        }
708
        if (libmav_msg_opt.value().get("target_component", target_component) ==
2,359✔
709
            mav::MessageResult::Success) {
710
            libmav_message.target_component = target_component;
1,812✔
711
        } else {
712
            libmav_message.target_component = 0;
550✔
713
        }
714

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

918
        auto new_configuration = get_configuration();
×
919

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

926
        return {ret, handle};
×
927

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

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

939
    return handle;
232✔
940
}
116✔
941

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

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

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

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

966
    if (new_configuration.get_always_send_heartbeats() &&
285✔
967
        !_configuration.get_always_send_heartbeats()) {
114✔
968
        start_sending_heartbeats();
58✔
969
    } else if (
113✔
970
        !new_configuration.get_always_send_heartbeats() &&
170✔
971
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
170✔
972
        stop_sending_heartbeats();
×
973
    }
974

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1055
    return handle;
106✔
1056
}
53✔
1057

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

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

1071
void MavsdkImpl::work_thread()
114✔
1072
{
1073
    while (!_should_exit) {
23,193✔
1074
        // Process incoming messages
1075
        process_messages();
22,853✔
1076

1077
        // Process incoming libmav messages
1078
        process_libmav_messages();
22,880✔
1079

1080
        // Run timers
1081
        timeout_handler.run_once();
22,885✔
1082
        call_every_handler.run_once();
22,955✔
1083

1084
        // Do component work
1085
        {
1086
            std::lock_guard lock(_server_components_mutex);
23,140✔
1087
            for (auto& it : _server_components) {
46,232✔
1088
                if (it.second != nullptr) {
23,191✔
1089
                    it.second->_impl->do_work();
23,103✔
1090
                }
1091
            }
1092
        }
22,914✔
1093

1094
        // Deliver outgoing messages
1095
        deliver_messages();
22,942✔
1096

1097
        // If no messages to send, check if there are messages to receive
1098
        std::unique_lock lock_received(_received_messages_mutex);
22,979✔
1099
        if (_received_messages.empty()) {
22,998✔
1100
            // No messages to process, wait for a signal or timeout
1101
            _received_messages_cv.wait_for(lock_received, std::chrono::milliseconds(10), [this]() {
22,765✔
1102
                return !_received_messages.empty() || _should_exit;
45,850✔
1103
            });
1104
        }
1105
    }
23,199✔
1106
}
152✔
1107

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

1225
    for (auto& it : _server_components) {
675✔
1226
        if (it.second != nullptr) {
338✔
1227
            it.second->_impl->send_heartbeat();
337✔
1228
        }
1229
    }
1230
}
338✔
1231

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

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

1244
Mavsdk::MavlinkMessage MavsdkImpl::libmav_to_mavsdk_message(const LibmavMessage& libmav_message)
4,686✔
1245
{
1246
    // Convert LibmavMessage to Mavsdk::MavlinkMessage (much simpler!)
1247
    Mavsdk::MavlinkMessage json_message;
4,686✔
1248
    json_message.message_name = libmav_message.message_name;
4,677✔
1249
    json_message.system_id = libmav_message.system_id;
4,684✔
1250
    json_message.component_id = libmav_message.component_id;
4,684✔
1251
    json_message.target_system = libmav_message.target_system;
4,684✔
1252
    json_message.target_component = libmav_message.target_component;
4,684✔
1253
    json_message.fields_json = libmav_message.fields_json; // Already populated!
4,684✔
1254

1255
    return json_message;
4,681✔
1256
}
1257

1258
bool MavsdkImpl::call_json_interception_callbacks(
4,683✔
1259
    const Mavsdk::MavlinkMessage& json_message,
1260
    std::vector<std::pair<Mavsdk::InterceptJsonHandle, Mavsdk::InterceptJsonCallback>>&
1261
        callback_list)
1262
{
1263
    bool keep_message = true;
4,683✔
1264

1265
    std::lock_guard<std::mutex> lock(_json_subscriptions_mutex);
4,683✔
1266
    for (const auto& subscription : callback_list) {
4,687✔
1267
        if (!subscription.second(json_message)) {
3✔
NEW
1268
            keep_message = false;
×
1269
        }
1270
    }
1271

1272
    return keep_message;
9,355✔
1273
}
4,674✔
1274

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

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

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

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

1317
Mavsdk::ConnectionErrorHandle
1318
MavsdkImpl::subscribe_connection_errors(Mavsdk::ConnectionErrorCallback callback)
×
1319
{
1320
    std::lock_guard lock(_mutex);
×
1321

1322
    const auto handle = _connections_errors_subscriptions.subscribe(callback);
×
1323

1324
    return handle;
×
1325
}
×
1326

1327
void MavsdkImpl::unsubscribe_connection_errors(Mavsdk::ConnectionErrorHandle handle)
×
1328
{
1329
    std::lock_guard lock(_mutex);
×
1330
    _connections_errors_subscriptions.unsubscribe(handle);
×
1331
}
×
1332

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

1338
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
2,361✔
1339
        return 0;
533✔
1340
    }
1341

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

1348
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,817✔
1349
}
1350

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

1356
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
41✔
1357
        return 0;
28✔
1358
    }
1359

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

1366
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
12✔
1367
}
1368

1369
Sender& MavsdkImpl::sender()
×
1370
{
1371
    std::lock_guard lock(_server_components_mutex);
×
1372
    return default_server_component_with_lock().sender();
×
1373
}
×
1374

1375
std::vector<Connection*> MavsdkImpl::get_connections() const
2,359✔
1376
{
1377
    std::lock_guard lock(_mutex);
2,359✔
1378
    std::vector<Connection*> connections;
2,360✔
1379
    for (const auto& connection_entry : _connections) {
4,680✔
1380
        connections.push_back(connection_entry.connection.get());
2,319✔
1381
    }
1382
    return connections;
2,359✔
1383
}
2,359✔
1384

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

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

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

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

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

1425
// Thread-safe parsing for LibmavReceiver
1426
std::optional<mav::Message> MavsdkImpl::parse_message_safe(
4,705✔
1427
    const uint8_t* buffer, size_t buffer_len, size_t& bytes_consumed) const
1428
{
1429
    std::lock_guard<std::mutex> lock(_message_set_mutex);
4,705✔
1430
    return _buffer_parser->parseMessage(buffer, buffer_len, bytes_consumed);
4,706✔
1431
}
4,704✔
1432

1433
mav::OptionalReference<const mav::MessageDefinition>
1434
MavsdkImpl::get_message_definition_safe(int message_id) const
4,644✔
1435
{
1436
    std::lock_guard<std::mutex> lock(_message_set_mutex);
4,644✔
1437
    return _message_set->getMessageDefinition(message_id);
4,647✔
1438
}
4,649✔
1439

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