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

mavlink / MAVSDK / 16665088909

01 Aug 2025 02:55AM UTC coverage: 46.166% (-0.1%) from 46.31%
16665088909

push

github

web-flow
Merge pull request #2630 from mavlink/pr-segfault-fixes

Stack-use-after-free and thread-safety fixes, CI additions, clang-format-19

241 of 320 new or added lines in 32 files covered. (75.31%)

39 existing lines in 10 files now uncovered.

16101 of 34876 relevant lines covered (46.17%)

361.1 hits per line

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

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

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

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

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

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

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

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

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

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

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

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

151
    return systems_result;
121✔
152
}
121✔
153

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

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

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

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

185
    if (timeout_s > 0.0) {
40✔
186
        if (fut.wait_for(std::chrono::milliseconds(int64_t(timeout_s * 1e3))) ==
40✔
187
            std::future_status::ready) {
188
            unsubscribe_on_new_system(handle);
40✔
189
            return fut.get();
40✔
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
}
40✔
201

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

206
    auto component_type = _configuration.get_component_type();
48✔
207
    switch (component_type) {
48✔
208
        case ComponentType::Autopilot:
48✔
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);
48✔
216
        default:
×
217
            LogErr() << "Unknown component type";
×
218
            return {};
×
219
    }
220
}
48✔
221

222
std::shared_ptr<ServerComponent>
223
MavsdkImpl::server_component_by_type(ComponentType server_component_type, unsigned instance)
48✔
224
{
225
    switch (server_component_type) {
48✔
226
        case ComponentType::Autopilot:
34✔
227
            if (instance == 0) {
34✔
228
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1);
34✔
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)
48✔
281
{
282
    if (component_id == 0) {
48✔
283
        LogErr() << "Server component with component ID 0 not allowed";
×
284
        return nullptr;
×
285
    }
286

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

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

292
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id_with_lock(uint8_t component_id)
198✔
293
{
294
    for (auto& it : _server_components) {
199✔
295
        if (it.first == component_id) {
97✔
296
            if (it.second != nullptr) {
96✔
297
                return it.second;
96✔
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>>(
102✔
305
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
204✔
306

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

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

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

327
    if (!targeted_only_at_us && heartbeat_check_ok) {
×
328
        unsigned successful_emissions = 0;
×
329
        for (auto& entry : _connections) {
×
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 ||
×
333
                !entry.connection->should_forward_messages()) {
×
334
                continue;
×
335
            }
336
            auto result = (*entry.connection).send_message(message);
×
337
            if (result.first) {
×
338
                successful_emissions++;
×
339
            } else {
340
                _connections_errors_subscriptions.queue(
×
341
                    Mavsdk::ConnectionError{result.second, entry.handle},
×
342
                    [this](const auto& func) { call_user_callback(func); });
×
343
            }
344
        }
×
345
        if (successful_emissions == 0) {
×
346
            LogErr() << "Message forwarding failed";
×
347
        }
348
    }
349
}
×
350

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

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

369
void MavsdkImpl::process_messages()
21,041✔
370
{
371
    std::lock_guard lock(_received_messages_mutex);
21,041✔
372
    while (!_received_messages.empty()) {
23,036✔
373
        auto message_copied = _received_messages.front();
2,152✔
374
        process_message(message_copied.message, message_copied.connection_ptr);
2,147✔
375
        _received_messages.pop();
2,155✔
376
    }
377
}
20,388✔
378

379
void MavsdkImpl::process_libmav_messages()
20,225✔
380
{
381
    std::lock_guard lock(_received_libmav_messages_mutex);
20,225✔
382
    while (!_received_libmav_messages.empty()) {
22,670✔
383
        auto message_copied = _received_libmav_messages.front();
2,146✔
384
        process_libmav_message(message_copied.message, message_copied.connection_ptr);
2,148✔
385
        _received_libmav_messages.pop();
2,151✔
386
    }
2,149✔
387
}
20,610✔
388

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

393
    if (_message_logging_on) {
2,152✔
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,152✔
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,153✔
405

406
        // This is a low level interface where incoming messages can be tampered
407
        // with or even dropped.
408
        {
409
            bool keep = true;
2,149✔
410
            {
411
                std::lock_guard<std::mutex> intercept_lock(_intercept_callbacks_mutex);
2,149✔
412
                if (_intercept_incoming_messages_callback != nullptr) {
2,151✔
413
                    keep = _intercept_incoming_messages_callback(message);
235✔
414
                }
415
            }
2,149✔
416

417
            if (!keep) {
2,155✔
418
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
32✔
419
                return;
32✔
420
            }
421
        }
422

423
        if (_should_exit) {
2,123✔
424
            // If we're meant to clean up, let's not try to acquire any more locks but bail.
425
            return;
×
426
        }
427

428
        /** @note: Forward message if option is enabled and multiple interfaces are connected.
429
         *  Performs message forwarding checks for every messages if message forwarding
430
         *  is enabled on at least one connection, and in case of a single forwarding connection,
431
         *  we check that it is not the one which received the current message.
432
         *
433
         * Conditions:
434
         * 1. At least 2 connections.
435
         * 2. At least 1 forwarding connection.
436
         * 3. At least 2 forwarding connections or current connection is not forwarding.
437
         */
438

439
        if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
2,120✔
440
            (mavsdk::Connection::forwarding_connections_count() > 1 ||
×
UNCOV
441
             !connection->should_forward_messages())) {
×
442
            if (_message_logging_on) {
×
443
                LogDebug() << "Forwarding message " << message.msgid << " from "
×
444
                           << static_cast<int>(message.sysid) << "/"
×
445
                           << static_cast<int>(message.compid);
×
446
            }
447
            forward_message(message, connection);
×
448
        }
449

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

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

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

475
        bool found_system = false;
2,119✔
476
        for (auto& system : _systems) {
2,116✔
477
            if (system.first == message.sysid) {
2,026✔
478
                system.second->system_impl()->add_new_component(message.compid);
2,029✔
479
                found_system = true;
2,025✔
480
                break;
2,025✔
481
            }
482
        }
483

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

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

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

509
    mavlink_message_handler.process_message(message);
2,118✔
510

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

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

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

529
    if (_message_logging_on) {
2,153✔
530
        LogDebug() << "Processing libmav message " << message.message_name << " from "
×
531
                   << static_cast<int>(message.system_id) << "/"
×
532
                   << static_cast<int>(message.component_id);
×
533
    }
534

535
    if (_should_exit) {
2,153✔
536
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
537
        return;
×
538
    }
539

540
    {
541
        std::lock_guard lock(_mutex);
2,152✔
542

543
        // Don't ever create a system with sysid 0.
544
        if (message.system_id == 0) {
2,145✔
545
            if (_message_logging_on) {
×
546
                LogDebug() << "Ignoring libmav message with sysid == 0";
×
547
            }
548
            return;
×
549
        }
550

551
        // Filter out QGroundControl messages similar to regular mavlink processing
552
        if (_configuration.get_component_type() == ComponentType::GroundStation &&
2,145✔
553
            message.system_id == 255 && message.component_id == MAV_COMP_ID_MISSIONPLANNER) {
2,144✔
554
            if (_message_logging_on) {
×
555
                LogDebug() << "Ignoring libmav messages from QGC as we are also a ground station";
×
556
            }
557
            return;
×
558
        }
559

560
        bool found_system = false;
2,144✔
561
        for (auto& system : _systems) {
2,144✔
562
            if (system.first == message.system_id) {
2,147✔
563
                system.second->system_impl()->add_new_component(message.component_id);
2,147✔
564
                found_system = true;
2,141✔
565
                break;
2,141✔
566
            }
567
        }
568

569
        if (!found_system) {
2,149✔
570
            if (_system_debugging) {
6✔
571
                LogWarn() << "Create new system/component from libmav " << (int)message.system_id
×
572
                          << "/" << (int)message.component_id;
×
573
            }
574
            make_system_with_component(message.system_id, message.component_id);
6✔
575

576
            // We now better talk back.
577
            start_sending_heartbeats();
6✔
578
        }
579

580
        if (_should_exit) {
2,149✔
581
            // Don't try to call at() if systems have already been destroyed
582
            // in destructor.
583
            return;
×
584
        }
585
    }
2,145✔
586

587
    // Distribute libmav message to systems for libmav-specific handling
588
    bool found_system = false;
2,152✔
589
    for (auto& system : _systems) {
4,302✔
590
        if (system.first == message.system_id) {
2,147✔
591
            if (_message_logging_on) {
2,147✔
592
                LogDebug() << "Distributing libmav message " << message.message_name
×
593
                           << " to SystemImpl for system " << system.first;
×
594
            }
595
            system.second->system_impl()->process_libmav_message(message);
2,147✔
596
            found_system = true;
2,150✔
597
            // Don't break - distribute to all matching system instances
598
        }
599
    }
600

601
    if (!found_system) {
2,149✔
602
        LogWarn() << "No system found for libmav message " << message.message_name
×
603
                  << " from system " << message.system_id;
×
604
    }
605
}
606

607
bool MavsdkImpl::send_message(mavlink_message_t& message)
2,307✔
608
{
609
    // Create a copy of the message to avoid reference issues
610
    mavlink_message_t message_copy = message;
2,307✔
611

612
    {
613
        std::lock_guard lock(_messages_to_send_mutex);
2,307✔
614
        _messages_to_send.push(std::move(message_copy));
2,307✔
615
    }
2,308✔
616

617
    // For heartbeat messages, we want to process them immediately to speed up system discovery
618
    if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
2,304✔
619
        // Trigger message processing in the work thread
620
        // This is a hint to process messages sooner, but doesn't block
621
        std::this_thread::yield();
274✔
622
    }
623

624
    return true;
2,307✔
625
}
626

627
void MavsdkImpl::deliver_messages()
23,338✔
628
{
629
    // Process messages one at a time to avoid holding the mutex while delivering
630
    while (true) {
631
        mavlink_message_t message;
632
        {
633
            std::lock_guard lock(_messages_to_send_mutex);
23,338✔
634
            if (_messages_to_send.empty()) {
22,953✔
635
                break;
20,786✔
636
            }
637
            message = _messages_to_send.front();
2,304✔
638
            _messages_to_send.pop();
2,307✔
639
        }
23,092✔
640
        deliver_message(message);
2,306✔
641
    }
2,307✔
642
}
20,599✔
643

644
void MavsdkImpl::deliver_message(mavlink_message_t& message)
2,307✔
645
{
646
    if (_message_logging_on) {
2,307✔
647
        LogDebug() << "Sending message " << message.msgid << " from "
×
648
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid)
×
649
                   << " to " << static_cast<int>(get_target_system_id(message)) << "/"
×
650
                   << static_cast<int>(get_target_component_id(message));
×
651
    }
652

653
    // This is a low level interface where outgoing messages can be tampered
654
    // with or even dropped.
655
    bool keep = true;
2,307✔
656
    {
657
        std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
2,307✔
658
        if (_intercept_outgoing_messages_callback != nullptr) {
2,304✔
659
            keep = _intercept_outgoing_messages_callback(message);
226✔
660
        }
661
    }
2,304✔
662

663
    if (!keep) {
2,304✔
664
        // We fake that everything was sent as instructed because
665
        // a potential loss would happen later, and we would not be informed
666
        // about it.
667
        LogDebug() << "Dropped outgoing message: " << int(message.msgid);
88✔
668
        return;
138✔
669
    }
670

671
    std::lock_guard lock(_mutex);
2,216✔
672

673
    if (_connections.empty()) {
2,216✔
674
        // We obviously can't send any messages without a connection added, so
675
        // we silently ignore this.
676
        return;
50✔
677
    }
678

679
    uint8_t successful_emissions = 0;
2,166✔
680
    for (auto& _connection : _connections) {
4,334✔
681
        const uint8_t target_system_id = get_target_system_id(message);
2,169✔
682

683
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
2,169✔
684
            continue;
×
685
        }
686
        const auto result = (*_connection.connection).send_message(message);
2,161✔
687
        if (result.first) {
2,169✔
688
            successful_emissions++;
2,169✔
689
        } else {
690
            _connections_errors_subscriptions.queue(
×
691
                Mavsdk::ConnectionError{result.second, _connection.handle},
×
692
                [this](const auto& func) { call_user_callback(func); });
×
693
        }
694
    }
2,169✔
695

696
    if (successful_emissions == 0) {
2,167✔
697
        LogErr() << "Sending message failed";
×
698
    }
699
}
2,216✔
700

701
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
100✔
702
    const std::string& connection_url, ForwardingOption forwarding_option)
703
{
704
    CliArg cli_arg;
100✔
705
    if (!cli_arg.parse(connection_url)) {
100✔
706
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
707
    }
708

709
    return std::visit(
100✔
710
        overloaded{
200✔
711
            [](std::monostate) {
×
712
                // Should not happen anyway.
713
                return std::pair<ConnectionResult, Mavsdk::ConnectionHandle>{
×
714
                    ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle()};
×
715
            },
716
            [this, forwarding_option](const CliArg::Udp& udp) {
98✔
717
                return add_udp_connection(udp, forwarding_option);
98✔
718
            },
719
            [this, forwarding_option](const CliArg::Tcp& tcp) {
2✔
720
                return add_tcp_connection(tcp, forwarding_option);
2✔
721
            },
722
            [this, forwarding_option](const CliArg::Serial& serial) {
×
723
                return add_serial_connection(
×
724
                    serial.path, serial.baudrate, serial.flow_control_enabled, forwarding_option);
×
725
            }},
726
        cli_arg.protocol);
100✔
727
}
100✔
728

729
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
730
MavsdkImpl::add_udp_connection(const CliArg::Udp& udp, ForwardingOption forwarding_option)
98✔
731
{
732
    auto new_conn = std::make_unique<UdpConnection>(
733
        [this](mavlink_message_t& message, Connection* connection) {
2,146✔
734
            receive_message(message, connection);
2,146✔
735
        },
2,148✔
736
        [this](const LibmavMessage& message, Connection* connection) {
2,149✔
737
            receive_libmav_message(message, connection);
2,149✔
738
        },
2,147✔
739
        *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
740
        udp.mode == CliArg::Udp::Mode::In ? udp.host : "0.0.0.0",
196✔
741
        udp.mode == CliArg::Udp::Mode::In ? udp.port : 0,
98✔
742
        forwarding_option);
98✔
743

744
    if (!new_conn) {
98✔
745
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
746
    }
747

748
    ConnectionResult ret = new_conn->start();
98✔
749

750
    if (ret != ConnectionResult::Success) {
98✔
751
        return {ret, Mavsdk::ConnectionHandle{}};
×
752
    }
753

754
    if (udp.mode == CliArg::Udp::Mode::Out) {
98✔
755
        // We need to add the IP rather than a hostname, otherwise we end up with two remotes:
756
        // one for the IP, and one for a hostname.
757
        auto remote_ip = resolve_hostname_to_ip(udp.host);
49✔
758

759
        if (!remote_ip) {
49✔
760
            return {ConnectionResult::DestinationIpUnknown, Mavsdk::ConnectionHandle{}};
×
761
        }
762

763
        new_conn->add_remote_to_keep(remote_ip.value(), udp.port);
49✔
764
        std::lock_guard lock(_mutex);
49✔
765

766
        // With a UDP remote, we need to initiate the connection by sending heartbeats.
767
        auto new_configuration = get_configuration();
49✔
768
        new_configuration.set_always_send_heartbeats(true);
49✔
769
        set_configuration(new_configuration);
49✔
770
    }
49✔
771

772
    auto handle = add_connection(std::move(new_conn));
98✔
773

774
    return {ConnectionResult::Success, handle};
98✔
775
}
98✔
776

777
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
778
MavsdkImpl::add_tcp_connection(const CliArg::Tcp& tcp, ForwardingOption forwarding_option)
2✔
779
{
780
    if (tcp.mode == CliArg::Tcp::Mode::Out) {
2✔
781
        auto new_conn = std::make_unique<TcpClientConnection>(
782
            [this](mavlink_message_t& message, Connection* connection) {
7✔
783
                receive_message(message, connection);
7✔
784
            },
7✔
785
            [this](const LibmavMessage& message, Connection* connection) {
7✔
786
                receive_libmav_message(message, connection);
7✔
787
            },
7✔
788
            *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
789
            tcp.host,
1✔
790
            tcp.port,
1✔
791
            forwarding_option);
1✔
792
        if (!new_conn) {
1✔
793
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
794
        }
795
        ConnectionResult ret = new_conn->start();
1✔
796
        if (ret == ConnectionResult::Success) {
1✔
797
            return {ret, add_connection(std::move(new_conn))};
1✔
798
        } else {
799
            return {ret, Mavsdk::ConnectionHandle{}};
×
800
        }
801
    } else {
1✔
802
        auto new_conn = std::make_unique<TcpServerConnection>(
803
            [this](mavlink_message_t& message, Connection* connection) {
13✔
804
                receive_message(message, connection);
13✔
805
            },
13✔
806
            [this](const LibmavMessage& message, Connection* connection) {
11✔
807
                receive_libmav_message(message, connection);
11✔
808
            },
11✔
809
            *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
810
            tcp.host,
1✔
811
            tcp.port,
1✔
812
            forwarding_option);
1✔
813
        if (!new_conn) {
1✔
814
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
815
        }
816
        ConnectionResult ret = new_conn->start();
1✔
817
        if (ret == ConnectionResult::Success) {
1✔
818
            return {ret, add_connection(std::move(new_conn))};
1✔
819
        } else {
820
            return {ret, Mavsdk::ConnectionHandle{}};
×
821
        }
822
    }
1✔
823
}
824

825
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
826
    const std::string& dev_path,
827
    int baudrate,
828
    bool flow_control,
829
    ForwardingOption forwarding_option)
830
{
831
    auto new_conn = std::make_unique<SerialConnection>(
832
        [this](mavlink_message_t& message, Connection* connection) {
×
833
            receive_message(message, connection);
×
834
        },
×
835
        [this](const LibmavMessage& message, Connection* connection) {
×
836
            receive_libmav_message(message, connection);
×
837
        },
×
838
        *this, // Pass MavsdkImpl reference for thread-safe MessageSet access
839
        dev_path,
840
        baudrate,
841
        flow_control,
842
        forwarding_option);
×
843
    if (!new_conn) {
×
844
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
845
    }
846
    ConnectionResult ret = new_conn->start();
×
847
    if (ret == ConnectionResult::Success) {
×
848
        auto handle = add_connection(std::move(new_conn));
×
849

850
        auto new_configuration = get_configuration();
×
851

852
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
853
        // to initiate the MAVLink connection by sending heartbeats.
854
        // Therefore, we override the default here and enable sending heartbeats.
855
        new_configuration.set_always_send_heartbeats(true);
×
856
        set_configuration(new_configuration);
×
857

858
        return {ret, handle};
×
859

860
    } else {
861
        return {ret, Mavsdk::ConnectionHandle{}};
×
862
    }
863
}
×
864

865
Mavsdk::ConnectionHandle MavsdkImpl::add_connection(std::unique_ptr<Connection>&& new_connection)
100✔
866
{
867
    std::lock_guard lock(_mutex);
100✔
868
    auto handle = _connections_handle_factory.create();
100✔
869
    _connections.emplace_back(ConnectionEntry{std::move(new_connection), handle});
100✔
870

871
    return handle;
200✔
872
}
100✔
873

874
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
×
875
{
876
    std::lock_guard lock(_mutex);
×
877

878
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
×
879
        return (entry.handle == handle);
×
880
    }));
881
}
×
882

883
Mavsdk::Configuration MavsdkImpl::get_configuration() const
49✔
884
{
885
    std::lock_guard configuration_lock(_mutex);
49✔
886
    return _configuration;
98✔
887
}
49✔
888

889
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
150✔
890
{
891
    std::lock_guard server_components_lock(_server_components_mutex);
150✔
892
    // We just point the default to the newly created component. This means
893
    // that the previous default component will be deleted if it is not
894
    // used/referenced anywhere.
895
    _default_server_component =
896
        server_component_by_id_with_lock(new_configuration.get_component_id());
150✔
897

898
    if (new_configuration.get_always_send_heartbeats() &&
249✔
899
        !_configuration.get_always_send_heartbeats()) {
99✔
900
        start_sending_heartbeats();
50✔
901
    } else if (
100✔
902
        !new_configuration.get_always_send_heartbeats() &&
151✔
903
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
151✔
904
        stop_sending_heartbeats();
×
905
    }
906

907
    _configuration = new_configuration;
150✔
908
    // We cache these values as atomic to avoid having to lock any mutex for them.
909
    _our_system_id = new_configuration.get_system_id();
150✔
910
    _our_component_id = new_configuration.get_component_id();
150✔
911
}
150✔
912

913
uint8_t MavsdkImpl::get_own_system_id() const
5,338✔
914
{
915
    return _our_system_id;
5,338✔
916
}
917

918
uint8_t MavsdkImpl::get_own_component_id() const
1,413✔
919
{
920
    return _our_component_id;
1,413✔
921
}
922

923
uint8_t MavsdkImpl::channel() const
×
924
{
925
    // TODO
926
    return 0;
×
927
}
928

929
Autopilot MavsdkImpl::autopilot() const
×
930
{
931
    // TODO
932
    return Autopilot::Px4;
×
933
}
934

935
// FIXME: this should be per component
936
uint8_t MavsdkImpl::get_mav_type() const
278✔
937
{
938
    return _configuration.get_mav_type();
278✔
939
}
940

941
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
100✔
942
{
943
    // Needs _systems_lock
944

945
    if (_should_exit) {
100✔
946
        // When the system got destroyed in the destructor, we have to give up.
947
        return;
×
948
    }
949

950
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
100✔
951
        LogDebug() << "Initializing connection to remote system...";
×
952
    } else {
953
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
200✔
954
                   << " Comp ID: " << static_cast<int>(comp_id);
100✔
955
    }
956

957
    // Make a system with its first component
958
    auto new_system = std::make_shared<System>(*this);
100✔
959
    new_system->init(system_id, comp_id);
100✔
960

961
    _systems.emplace_back(system_id, new_system);
100✔
962
}
100✔
963

964
void MavsdkImpl::notify_on_discover()
100✔
965
{
966
    // Queue the callbacks without holding the mutex to avoid deadlocks
967
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
150✔
968
}
100✔
969

970
void MavsdkImpl::notify_on_timeout()
×
971
{
972
    // Queue the callbacks without holding the mutex to avoid deadlocks
973
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
974
}
×
975

976
Mavsdk::NewSystemHandle
977
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
50✔
978
{
979
    std::lock_guard lock(_mutex);
50✔
980

981
    const auto handle = _new_system_callbacks.subscribe(callback);
50✔
982

983
    if (is_any_system_connected()) {
50✔
984
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
985
    }
986

987
    return handle;
100✔
988
}
50✔
989

990
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
49✔
991
{
992
    _new_system_callbacks.unsubscribe(handle);
49✔
993
}
49✔
994

995
bool MavsdkImpl::is_any_system_connected() const
50✔
996
{
997
    std::vector<std::shared_ptr<System>> connected_systems = systems();
50✔
998
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
50✔
999
        return system->is_connected();
×
1000
    });
50✔
1001
}
50✔
1002

1003
void MavsdkImpl::work_thread()
101✔
1004
{
1005
    while (!_should_exit) {
21,037✔
1006
        // Process incoming messages
1007
        process_messages();
20,740✔
1008

1009
        // Process incoming libmav messages
1010
        process_libmav_messages();
20,839✔
1011

1012
        // Run timers
1013
        timeout_handler.run_once();
20,492✔
1014
        call_every_handler.run_once();
20,795✔
1015

1016
        // Do component work
1017
        {
1018
            std::lock_guard lock(_server_components_mutex);
20,905✔
1019
            for (auto& it : _server_components) {
41,721✔
1020
                if (it.second != nullptr) {
21,068✔
1021
                    it.second->_impl->do_work();
20,919✔
1022
                }
1023
            }
1024
        }
20,338✔
1025

1026
        // Deliver outgoing messages
1027
        deliver_messages();
20,475✔
1028

1029
        // If no messages to send, check if there are messages to receive
1030
        std::unique_lock lock_received(_received_messages_mutex);
20,609✔
1031
        if (_received_messages.empty()) {
20,614✔
1032
            // No messages to process, wait for a signal or timeout
1033
            _received_messages_cv.wait_for(lock_received, std::chrono::milliseconds(10), [this]() {
20,455✔
1034
                return !_received_messages.empty() || _should_exit;
41,645✔
1035
            });
1036
        }
1037
    }
21,029✔
1038
}
73✔
1039

1040
void MavsdkImpl::call_user_callback_located(
1,087✔
1041
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1042
{
1043
    // Don't enqueue callbacks if we're shutting down
1044
    if (_should_exit) {
1,087✔
1045
        return;
×
1046
    }
1047

1048
    auto callback_size = _user_callback_queue.size();
1,087✔
1049
    if (callback_size == 10) {
1,087✔
1050
        LogWarn()
×
1051
            << "User callback queue too slow.\n"
1052
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1053

1054
    } else if (callback_size == 99) {
1,087✔
1055
        LogErr()
×
1056
            << "User callback queue overflown\n"
1057
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1058

1059
    } else if (callback_size == 100) {
1,087✔
1060
        return;
×
1061
    }
1062

1063
    // We only need to keep track of filename and linenumber if we're actually debugging this.
1064
    UserCallback user_callback =
1065
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
2,174✔
1066

1067
    _user_callback_queue.push_back(std::make_shared<UserCallback>(user_callback));
1,087✔
1068
}
1,087✔
1069

1070
void MavsdkImpl::process_user_callbacks_thread()
101✔
1071
{
1072
    while (!_should_exit) {
1,289✔
1073
        UserCallback callback;
1,188✔
1074
        {
1075
            LockedQueue<UserCallback>::Guard guard(_user_callback_queue);
1,188✔
1076
            auto ptr = guard.wait_and_pop_front();
1,188✔
1077
            if (!ptr) {
1,188✔
1078
                continue;
101✔
1079
            }
1080
            // We need to get a copy instead of just a shared_ptr because the queue might
1081
            // be invalidated when the lock is released.
1082
            callback = *ptr;
1,086✔
1083
        }
1,289✔
1084

1085
        // Check if we're in the process of shutting down before executing the callback
1086
        if (_should_exit) {
1,086✔
1087
            continue;
×
1088
        }
1089

1090
        const double timeout_s = 1.0;
1,087✔
1091
        auto cookie = timeout_handler.add(
1,087✔
1092
            [&]() {
×
1093
                if (_callback_debugging) {
×
NEW
1094
                    LogWarn() << "Callback called from " << callback.filename << ":"
×
NEW
1095
                              << callback.linenumber << " took more than " << timeout_s
×
1096
                              << " second to run.";
×
1097
                    fflush(stdout);
×
1098
                    fflush(stderr);
×
1099
                    abort();
×
1100
                } else {
1101
                    LogWarn()
×
1102
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
1103
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1104
                }
1105
            },
×
1106
            timeout_s);
1107
        callback.func();
1,087✔
1108
        timeout_handler.remove(cookie);
1,087✔
1109
    }
1,188✔
1110
}
101✔
1111

1112
void MavsdkImpl::start_sending_heartbeats()
250✔
1113
{
1114
    // Check if we're in the process of shutting down
1115
    if (_should_exit) {
250✔
1116
        return;
×
1117
    }
1118

1119
    // Before sending out first heartbeats we need to make sure we have a
1120
    // default server component.
1121
    default_server_component_impl();
250✔
1122

1123
    {
1124
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
250✔
1125
        call_every_handler.remove(_heartbeat_send_cookie);
250✔
1126
        _heartbeat_send_cookie =
250✔
1127
            call_every_handler.add([this]() { send_heartbeats(); }, HEARTBEAT_SEND_INTERVAL_S);
527✔
1128
    }
250✔
1129
}
1130

1131
void MavsdkImpl::stop_sending_heartbeats()
×
1132
{
1133
    if (!_configuration.get_always_send_heartbeats()) {
×
1134
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
×
1135
        call_every_handler.remove(_heartbeat_send_cookie);
×
1136
    }
×
1137
}
×
1138

1139
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
1,141✔
1140
{
1141
    std::lock_guard lock(_server_components_mutex);
1,141✔
1142
    return default_server_component_with_lock();
1,141✔
1143
}
1,141✔
1144

1145
ServerComponentImpl& MavsdkImpl::default_server_component_with_lock()
1,141✔
1146
{
1147
    if (_default_server_component == nullptr) {
1,141✔
1148
        _default_server_component = server_component_by_id_with_lock(_our_component_id);
×
1149
    }
1150
    return *_default_server_component->_impl;
1,140✔
1151
}
1152

1153
void MavsdkImpl::send_heartbeats()
277✔
1154
{
1155
    std::lock_guard lock(_server_components_mutex);
277✔
1156

1157
    for (auto& it : _server_components) {
552✔
1158
        if (it.second != nullptr) {
278✔
1159
            it.second->_impl->send_heartbeat();
276✔
1160
        }
1161
    }
1162
}
273✔
1163

1164
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
22✔
1165
{
1166
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
22✔
1167
    _intercept_incoming_messages_callback = callback;
22✔
1168
}
22✔
1169

1170
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
1171
{
1172
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
14✔
1173
    _intercept_outgoing_messages_callback = callback;
14✔
1174
}
14✔
1175

1176
Mavsdk::ConnectionErrorHandle
1177
MavsdkImpl::subscribe_connection_errors(Mavsdk::ConnectionErrorCallback callback)
×
1178
{
1179
    std::lock_guard lock(_mutex);
×
1180

1181
    const auto handle = _connections_errors_subscriptions.subscribe(callback);
×
1182

1183
    return handle;
×
1184
}
×
1185

1186
void MavsdkImpl::unsubscribe_connection_errors(Mavsdk::ConnectionErrorHandle handle)
×
1187
{
1188
    std::lock_guard lock(_mutex);
×
1189
    _connections_errors_subscriptions.unsubscribe(handle);
×
1190
}
×
1191

1192
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
2,169✔
1193
{
1194
    // Checks whether connection knows target system ID by extracting target system if set.
1195
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
2,169✔
1196

1197
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
2,170✔
1198
        return 0;
427✔
1199
    }
1200

1201
    // Don't look at the target system offset if it is outside the payload length.
1202
    // This can happen if the fields are trimmed.
1203
    if (meta->target_system_ofs >= message.len) {
1,743✔
1204
        return 0;
5✔
1205
    }
1206

1207
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,738✔
1208
}
1209

1210
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
×
1211
{
1212
    // Checks whether connection knows target system ID by extracting target system if set.
1213
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
×
1214

1215
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
×
1216
        return 0;
×
1217
    }
1218

1219
    // Don't look at the target component offset if it is outside the payload length.
1220
    // This can happen if the fields are trimmed.
1221
    if (meta->target_component_ofs >= message.len) {
×
1222
        return 0;
×
1223
    }
1224

1225
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
×
1226
}
1227

1228
Sender& MavsdkImpl::sender()
×
1229
{
1230
    std::lock_guard lock(_server_components_mutex);
×
1231
    return default_server_component_with_lock().sender();
×
1232
}
×
1233

1234
std::vector<Connection*> MavsdkImpl::get_connections() const
×
1235
{
1236
    std::vector<Connection*> connections;
×
1237
    for (const auto& connection_entry : _connections) {
×
1238
        connections.push_back(connection_entry.connection.get());
×
1239
    }
1240
    return connections;
×
1241
}
1242

1243
mav::MessageSet& MavsdkImpl::get_message_set() const
8✔
1244
{
1245
    // Note: This returns a reference to MessageSet without locking.
1246
    // Thread safety for MessageSet operations must be ensured by:
1247
    // 1. Using load_custom_xml_to_message_set() for write operations (XML loading)
1248
    // 2. libmav MessageSet should be internally thread-safe for read operations
1249
    // 3. If race conditions persist, consider implementing a thread-safe MessageSet wrapper
1250
    return *_message_set;
8✔
1251
}
1252

1253
bool MavsdkImpl::load_custom_xml_to_message_set(const std::string& xml_content)
2✔
1254
{
1255
    std::lock_guard<std::mutex> lock(_message_set_mutex);
2✔
1256
    auto result = _message_set->addFromXMLString(xml_content, false /* recursive_open_includes */);
2✔
1257
    return result == ::mav::MessageSetResult::Success;
4✔
1258
}
2✔
1259

1260
// Thread-safe MessageSet read operations
NEW
1261
std::optional<std::string> MavsdkImpl::message_id_to_name_safe(uint32_t id) const
×
1262
{
NEW
1263
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
NEW
1264
    auto message_def = _message_set->getMessageDefinition(static_cast<int>(id));
×
NEW
1265
    if (message_def) {
×
NEW
1266
        return message_def.get().name();
×
1267
    }
NEW
1268
    return std::nullopt;
×
NEW
1269
}
×
1270

NEW
1271
std::optional<int> MavsdkImpl::message_name_to_id_safe(const std::string& name) const
×
1272
{
NEW
1273
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
NEW
1274
    return _message_set->idForMessage(name);
×
NEW
1275
}
×
1276

NEW
1277
std::optional<mav::Message> MavsdkImpl::create_message_safe(const std::string& message_name) const
×
1278
{
NEW
1279
    std::lock_guard<std::mutex> lock(_message_set_mutex);
×
NEW
1280
    return _message_set->create(message_name);
×
NEW
1281
}
×
1282

1283
// Thread-safe parsing for LibmavReceiver
1284
std::optional<mav::Message> MavsdkImpl::parse_message_safe(
2,167✔
1285
    const uint8_t* buffer, size_t buffer_len, size_t& bytes_consumed) const
1286
{
1287
    std::lock_guard<std::mutex> lock(_message_set_mutex);
2,167✔
1288
    return _buffer_parser->parseMessage(buffer, buffer_len, bytes_consumed);
2,165✔
1289
}
2,165✔
1290

1291
mav::OptionalReference<const mav::MessageDefinition>
1292
MavsdkImpl::get_message_definition_safe(int message_id) const
2,166✔
1293
{
1294
    std::lock_guard<std::mutex> lock(_message_set_mutex);
2,166✔
1295
    return _message_set->getMessageDefinition(message_id);
2,163✔
1296
}
2,165✔
1297

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