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

mavlink / MAVSDK / 16479917829

23 Jul 2025 07:23PM UTC coverage: 45.097% (+0.004%) from 45.093%
16479917829

push

github

web-flow
Merge pull request #2622 from JohanOlsson99/main

Build error windows without JOM

15384 of 34113 relevant lines covered (45.1%)

290.38 hits per line

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

62.48
/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

22
namespace mavsdk {
23

24
template class CallbackList<>;
25

26
MavsdkImpl::MavsdkImpl(const Mavsdk::Configuration& configuration) :
87✔
27
    timeout_handler(time),
87✔
28
    call_every_handler(time)
174✔
29
{
30
    LogInfo() << "MAVSDK version: " << mavsdk_version;
87✔
31

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

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

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

53
    set_configuration(configuration);
87✔
54

55
    // Start the user callback thread first, so it is ready for anything generated by
56
    // the work thread.
57

58
    _process_user_callbacks_thread =
174✔
59
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
87✔
60

61
    _work_thread = new std::thread(&MavsdkImpl::work_thread, this);
87✔
62
}
87✔
63

64
MavsdkImpl::~MavsdkImpl()
87✔
65
{
66
    {
67
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
87✔
68
        call_every_handler.remove(_heartbeat_send_cookie);
87✔
69
    }
87✔
70

71
    _should_exit = true;
87✔
72

73
    // Stop work first because we don't want to trigger anything that would
74
    // potentially want to call into user code.
75

76
    if (_work_thread != nullptr) {
87✔
77
        _work_thread->join();
87✔
78
        delete _work_thread;
87✔
79
        _work_thread = nullptr;
87✔
80
    }
81

82
    if (_process_user_callbacks_thread != nullptr) {
87✔
83
        _user_callback_queue.stop();
87✔
84
        _process_user_callbacks_thread->join();
87✔
85
        delete _process_user_callbacks_thread;
87✔
86
        _process_user_callbacks_thread = nullptr;
87✔
87
    }
88

89
    std::lock_guard lock(_mutex);
87✔
90

91
    _systems.clear();
87✔
92
    _connections.clear();
87✔
93
}
174✔
94

95
std::string MavsdkImpl::version()
1✔
96
{
97
    static unsigned version_counter = 0;
98

99
    ++version_counter;
1✔
100

101
    switch (version_counter) {
1✔
102
        case 10:
×
103
            return "You were wondering about the name of this library?";
×
104
        case 11:
×
105
            return "Let's look at the history:";
×
106
        case 12:
×
107
            return "DroneLink";
×
108
        case 13:
×
109
            return "DroneCore";
×
110
        case 14:
×
111
            return "DronecodeSDK";
×
112
        case 15:
×
113
            return "MAVSDK";
×
114
        case 16:
×
115
            return "And that's it...";
×
116
        case 17:
×
117
            return "At least for now ¯\\_(ツ)_/¯.";
×
118
        default:
1✔
119
            return mavsdk_version;
1✔
120
    }
121
}
122

123
std::vector<std::shared_ptr<System>> MavsdkImpl::systems() const
86✔
124
{
125
    std::vector<std::shared_ptr<System>> systems_result{};
86✔
126

127
    std::lock_guard lock(_mutex);
86✔
128
    for (auto& system : _systems) {
129✔
129
        // We ignore the 0 entry because it's just a null system.
130
        // It's only created because the older, deprecated API needs a
131
        // reference.
132
        if (system.first == 0) {
43✔
133
            continue;
×
134
        }
135
        systems_result.push_back(system.second);
43✔
136
    }
137

138
    return systems_result;
86✔
139
}
86✔
140

141
std::optional<std::shared_ptr<System>> MavsdkImpl::first_autopilot(double timeout_s)
33✔
142
{
143
    {
144
        std::lock_guard lock(_mutex);
33✔
145
        for (auto system : _systems) {
33✔
146
            if (system.second->is_connected() && system.second->has_autopilot()) {
×
147
                return system.second;
×
148
            }
149
        }
×
150
    }
33✔
151

152
    if (timeout_s == 0.0) {
33✔
153
        // Don't wait at all.
154
        return {};
×
155
    }
156

157
    auto prom = std::promise<std::shared_ptr<System>>();
33✔
158

159
    std::once_flag flag;
33✔
160
    auto handle = subscribe_on_new_system([this, &prom, &flag]() {
66✔
161
        // Check all systems, not just the first one
162
        auto all_systems = systems();
33✔
163
        for (auto& system : all_systems) {
33✔
164
            if (system->is_connected() && system->has_autopilot()) {
33✔
165
                std::call_once(flag, [&prom, &system]() { prom.set_value(system); });
66✔
166
                break;
33✔
167
            }
168
        }
169
    });
66✔
170

171
    auto fut = prom.get_future();
33✔
172

173
    if (timeout_s > 0.0) {
33✔
174
        if (fut.wait_for(std::chrono::milliseconds(int64_t(timeout_s * 1e3))) ==
33✔
175
            std::future_status::ready) {
176
            unsubscribe_on_new_system(handle);
33✔
177
            return fut.get();
33✔
178

179
        } else {
180
            unsubscribe_on_new_system(handle);
×
181
            return std::nullopt;
×
182
        }
183
    } else {
184
        fut.wait();
×
185
        unsubscribe_on_new_system(handle);
×
186
        return std::optional(fut.get());
×
187
    }
188
}
33✔
189

190
std::shared_ptr<ServerComponent> MavsdkImpl::server_component(unsigned instance)
47✔
191
{
192
    std::lock_guard lock(_mutex);
47✔
193

194
    auto component_type = _configuration.get_component_type();
47✔
195
    switch (component_type) {
47✔
196
        case ComponentType::Autopilot:
47✔
197
        case ComponentType::GroundStation:
198
        case ComponentType::CompanionComputer:
199
        case ComponentType::Camera:
200
        case ComponentType::Gimbal:
201
        case ComponentType::RemoteId:
202
        case ComponentType::Custom:
203
            return server_component_by_type(component_type, instance);
47✔
204
        default:
×
205
            LogErr() << "Unknown component type";
×
206
            return {};
×
207
    }
208
}
47✔
209

210
std::shared_ptr<ServerComponent>
211
MavsdkImpl::server_component_by_type(ComponentType server_component_type, unsigned instance)
47✔
212
{
213
    switch (server_component_type) {
47✔
214
        case ComponentType::Autopilot:
33✔
215
            if (instance == 0) {
33✔
216
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1);
33✔
217
            } else {
218
                LogErr() << "Only autopilot instance 0 is valid";
×
219
                return {};
×
220
            }
221

222
        case ComponentType::GroundStation:
×
223
            if (instance == 0) {
×
224
                return server_component_by_id(MAV_COMP_ID_MISSIONPLANNER);
×
225
            } else {
226
                LogErr() << "Only one ground station supported at this time";
×
227
                return {};
×
228
            }
229

230
        case ComponentType::CompanionComputer:
1✔
231
            if (instance == 0) {
1✔
232
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER);
1✔
233
            } else if (instance == 1) {
×
234
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER2);
×
235
            } else if (instance == 2) {
×
236
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER3);
×
237
            } else if (instance == 3) {
×
238
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER4);
×
239
            } else {
240
                LogErr() << "Only companion computer 0..3 are supported";
×
241
                return {};
×
242
            }
243

244
        case ComponentType::Camera:
13✔
245
            if (instance == 0) {
13✔
246
                return server_component_by_id(MAV_COMP_ID_CAMERA);
13✔
247
            } else if (instance == 1) {
×
248
                return server_component_by_id(MAV_COMP_ID_CAMERA2);
×
249
            } else if (instance == 2) {
×
250
                return server_component_by_id(MAV_COMP_ID_CAMERA3);
×
251
            } else if (instance == 3) {
×
252
                return server_component_by_id(MAV_COMP_ID_CAMERA4);
×
253
            } else if (instance == 4) {
×
254
                return server_component_by_id(MAV_COMP_ID_CAMERA5);
×
255
            } else if (instance == 5) {
×
256
                return server_component_by_id(MAV_COMP_ID_CAMERA6);
×
257
            } else {
258
                LogErr() << "Only camera 0..5 are supported";
×
259
                return {};
×
260
            }
261

262
        default:
×
263
            LogErr() << "Unknown server component type";
×
264
            return {};
×
265
    }
266
}
267

268
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id(uint8_t component_id)
47✔
269
{
270
    if (component_id == 0) {
47✔
271
        LogErr() << "Server component with component ID 0 not allowed";
×
272
        return nullptr;
×
273
    }
274

275
    std::lock_guard lock(_server_components_mutex);
47✔
276

277
    return server_component_by_id_with_lock(component_id);
47✔
278
}
47✔
279

280
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id_with_lock(uint8_t component_id)
176✔
281
{
282
    for (auto& it : _server_components) {
177✔
283
        if (it.first == component_id) {
89✔
284
            if (it.second != nullptr) {
88✔
285
                return it.second;
88✔
286
            } else {
287
                it.second = std::make_shared<ServerComponent>(*this, component_id);
×
288
            }
289
        }
290
    }
291

292
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
176✔
293
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
176✔
294

295
    return _server_components.back().second;
88✔
296
}
297

298
void MavsdkImpl::forward_message(mavlink_message_t& message, Connection* connection)
×
299
{
300
    // Forward_message Function implementing Mavlink routing rules.
301
    // See https://mavlink.io/en/guide/routing.html
302

303
    bool forward_heartbeats_enabled = true;
×
304
    const uint8_t target_system_id = get_target_system_id(message);
×
305
    const uint8_t target_component_id = get_target_component_id(message);
×
306

307
    // If it's a message only for us, we keep it, otherwise, we forward it.
308
    const bool targeted_only_at_us =
309
        (target_system_id == get_own_system_id() && target_component_id == get_own_component_id());
×
310

311
    // We don't forward heartbeats unless it's specifically enabled.
312
    const bool heartbeat_check_ok =
×
313
        (message.msgid != MAVLINK_MSG_ID_HEARTBEAT || forward_heartbeats_enabled);
×
314

315
    if (!targeted_only_at_us && heartbeat_check_ok) {
×
316
        unsigned successful_emissions = 0;
×
317
        for (auto& entry : _connections) {
×
318
            // Check whether the connection is not the one from which we received the message.
319
            // And also check if the connection was set to forward messages.
320
            if (entry.connection.get() == connection ||
×
321
                !entry.connection->should_forward_messages()) {
×
322
                continue;
×
323
            }
324
            auto result = (*entry.connection).send_message(message);
×
325
            if (result.first) {
×
326
                successful_emissions++;
×
327
            } else {
328
                _connections_errors_subscriptions.queue(
×
329
                    Mavsdk::ConnectionError{result.second, entry.handle},
×
330
                    [this](const auto& func) { call_user_callback(func); });
×
331
            }
332
        }
×
333
        if (successful_emissions == 0) {
×
334
            LogErr() << "Message forwarding failed";
×
335
        }
336
    }
337
}
×
338

339
void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connection)
2,102✔
340
{
341
    {
342
        std::lock_guard lock(_received_messages_mutex);
2,102✔
343
        _received_messages.emplace(ReceivedMessage{std::move(message), connection});
2,105✔
344
    }
2,106✔
345
    _received_messages_cv.notify_one();
2,105✔
346
}
2,106✔
347

348
void MavsdkImpl::process_messages()
20,365✔
349
{
350
    std::lock_guard lock(_received_messages_mutex);
20,365✔
351
    while (!_received_messages.empty()) {
22,095✔
352
        auto message_copied = _received_messages.front();
2,095✔
353
        process_message(message_copied.message, message_copied.connection_ptr);
2,095✔
354
        _received_messages.pop();
2,095✔
355
    }
356
}
19,804✔
357

358
void MavsdkImpl::process_message(mavlink_message_t& message, Connection* connection)
2,095✔
359
{
360
    // Assumes _received_messages_mutex
361

362
    if (_message_logging_on) {
2,095✔
363
        LogDebug() << "Processing message " << message.msgid << " from "
×
364
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
365
    }
366

367
    if (_should_exit) {
2,095✔
368
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
369
        return;
×
370
    }
371

372
    {
373
        std::lock_guard lock(_mutex);
2,095✔
374

375
        // This is a low level interface where incoming messages can be tampered
376
        // with or even dropped.
377
        {
378
            bool keep = true;
2,094✔
379
            {
380
                std::lock_guard<std::mutex> intercept_lock(_intercept_callbacks_mutex);
2,094✔
381
                if (_intercept_incoming_messages_callback != nullptr) {
2,095✔
382
                    keep = _intercept_incoming_messages_callback(message);
241✔
383
                }
384
            }
2,094✔
385

386
            if (!keep) {
2,094✔
387
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
33✔
388
                return;
33✔
389
            }
390
        }
391

392
        if (_should_exit) {
2,061✔
393
            // If we're meant to clean up, let's not try to acquire any more locks but bail.
394
            return;
×
395
        }
396

397
        /** @note: Forward message if option is enabled and multiple interfaces are connected.
398
         *  Performs message forwarding checks for every messages if message forwarding
399
         *  is enabled on at least one connection, and in case of a single forwarding connection,
400
         *  we check that it is not the one which received the current message.
401
         *
402
         * Conditions:
403
         * 1. At least 2 connections.
404
         * 2. At least 1 forwarding connection.
405
         * 3. At least 2 forwarding connections or current connection is not forwarding.
406
         */
407

408
        if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
2,062✔
409
            (mavsdk::Connection::forwarding_connections_count() > 1 ||
×
410
             !connection->should_forward_messages())) {
×
411
            if (_message_logging_on) {
×
412
                LogDebug() << "Forwarding message " << message.msgid << " from "
×
413
                           << static_cast<int>(message.sysid) << "/"
×
414
                           << static_cast<int>(message.compid);
×
415
            }
416
            forward_message(message, connection);
×
417
        }
418

419
        // Don't ever create a system with sysid 0.
420
        if (message.sysid == 0) {
2,061✔
421
            if (_message_logging_on) {
×
422
                LogDebug() << "Ignoring message with sysid == 0";
×
423
            }
424
            return;
×
425
        }
426

427
        // Filter out messages by QGroundControl, however, only do that if MAVSDK
428
        // is also implementing a ground station and not if it is used in another
429
        // configuration, e.g. on a companion.
430
        //
431
        // This is a workaround because PX4 started forwarding messages between
432
        // mavlink instances which leads to existing implementations (including
433
        // examples and integration tests) to connect to QGroundControl by accident
434
        // instead of PX4 because the check `has_autopilot()` is not used.
435

436
        if (_configuration.get_component_type() == ComponentType::GroundStation &&
2,061✔
437
            message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
2,061✔
438
            if (_message_logging_on) {
×
439
                LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
440
            }
441
            return;
×
442
        }
443

444
        bool found_system = false;
2,061✔
445
        for (auto& system : _systems) {
2,061✔
446
            if (system.first == message.sysid) {
1,976✔
447
                system.second->system_impl()->add_new_component(message.compid);
1,976✔
448
                found_system = true;
1,976✔
449
                break;
1,976✔
450
            }
451
        }
452

453
        if (!found_system) {
2,062✔
454
            if (_system_debugging) {
86✔
455
                LogWarn() << "Create new system/component " << (int)message.sysid << "/"
×
456
                          << (int)message.compid;
×
457
                LogWarn() << "From message " << (int)message.msgid << " with len "
×
458
                          << (int)message.len;
×
459
                std::string bytes = "";
×
460
                for (unsigned i = 0; i < 12 + message.len; ++i) {
×
461
                    bytes += std::to_string(reinterpret_cast<uint8_t*>(&message)[i]) + ' ';
×
462
                }
463
                LogWarn() << "Bytes: " << bytes;
×
464
            }
×
465
            make_system_with_component(message.sysid, message.compid);
86✔
466

467
            // We now better talk back.
468
            start_sending_heartbeats();
86✔
469
        }
470

471
        if (_should_exit) {
2,062✔
472
            // Don't try to call at() if systems have already been destroyed
473
            // in destructor.
474
            return;
×
475
        }
476
    }
2,095✔
477

478
    mavlink_message_handler.process_message(message);
2,062✔
479

480
    for (auto& system : _systems) {
2,059✔
481
        if (system.first == message.sysid) {
2,059✔
482
            system.second->system_impl()->process_mavlink_message(message);
2,061✔
483
            break;
2,062✔
484
        }
485
    }
486
}
487

488
bool MavsdkImpl::send_message(mavlink_message_t& message)
2,234✔
489
{
490
    // Create a copy of the message to avoid reference issues
491
    mavlink_message_t message_copy = message;
2,234✔
492

493
    {
494
        std::lock_guard lock(_messages_to_send_mutex);
2,235✔
495
        _messages_to_send.push(std::move(message_copy));
2,235✔
496
    }
2,232✔
497

498
    // For heartbeat messages, we want to process them immediately to speed up system discovery
499
    if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
2,236✔
500
        // Trigger message processing in the work thread
501
        // This is a hint to process messages sooner, but doesn't block
502
        std::this_thread::yield();
244✔
503
    }
504

505
    return true;
2,236✔
506
}
507

508
void MavsdkImpl::deliver_messages()
22,570✔
509
{
510
    // Process messages one at a time to avoid holding the mutex while delivering
511
    while (true) {
512
        mavlink_message_t message;
22,570✔
513
        {
514
            std::lock_guard lock(_messages_to_send_mutex);
22,373✔
515
            if (_messages_to_send.empty()) {
22,170✔
516
                break;
20,114✔
517
            }
518
            message = _messages_to_send.front();
2,235✔
519
            _messages_to_send.pop();
2,235✔
520
        }
22,346✔
521
        deliver_message(message);
2,236✔
522
    }
2,236✔
523
}
19,590✔
524

525
void MavsdkImpl::deliver_message(mavlink_message_t& message)
2,236✔
526
{
527
    if (_message_logging_on) {
2,236✔
528
        LogDebug() << "Sending message " << message.msgid << " from "
×
529
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid)
×
530
                   << " to " << static_cast<int>(get_target_system_id(message)) << "/"
×
531
                   << static_cast<int>(get_target_component_id(message));
×
532
    }
533

534
    // This is a low level interface where outgoing messages can be tampered
535
    // with or even dropped.
536
    bool keep = true;
2,236✔
537
    {
538
        std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
2,236✔
539
        if (_intercept_outgoing_messages_callback != nullptr) {
2,234✔
540
            keep = _intercept_outgoing_messages_callback(message);
220✔
541
        }
542
    }
2,235✔
543

544
    if (!keep) {
2,235✔
545
        // We fake that everything was sent as instructed because
546
        // a potential loss would happen later, and we would not be informed
547
        // about it.
548
        LogDebug() << "Dropped outgoing message: " << int(message.msgid);
87✔
549
        return;
87✔
550
    }
551

552
    std::lock_guard lock(_mutex);
2,148✔
553

554
    if (_connections.empty()) {
2,148✔
555
        // We obviously can't send any messages without a connection added, so
556
        // we silently ignore this.
557
        return;
43✔
558
    }
559

560
    uint8_t successful_emissions = 0;
2,105✔
561
    for (auto& _connection : _connections) {
4,210✔
562
        const uint8_t target_system_id = get_target_system_id(message);
2,106✔
563

564
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
2,105✔
565
            continue;
×
566
        }
567
        const auto result = (*_connection.connection).send_message(message);
2,103✔
568
        if (result.first) {
2,106✔
569
            successful_emissions++;
2,106✔
570
        } else {
571
            _connections_errors_subscriptions.queue(
×
572
                Mavsdk::ConnectionError{result.second, _connection.handle},
×
573
                [this](const auto& func) { call_user_callback(func); });
×
574
        }
575
    }
2,106✔
576

577
    if (successful_emissions == 0) {
2,106✔
578
        LogErr() << "Sending message failed";
×
579
    }
580
}
2,149✔
581

582
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
86✔
583
    const std::string& connection_url, ForwardingOption forwarding_option)
584
{
585
    CliArg cli_arg;
86✔
586
    if (!cli_arg.parse(connection_url)) {
86✔
587
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
588
    }
589

590
    return std::visit(
86✔
591
        overloaded{
172✔
592
            [](std::monostate) {
×
593
                // Should not happen anyway.
594
                return std::pair<ConnectionResult, Mavsdk::ConnectionHandle>{
×
595
                    ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle()};
×
596
            },
597
            [this, forwarding_option](const CliArg::Udp& udp) {
84✔
598
                return add_udp_connection(udp, forwarding_option);
84✔
599
            },
600
            [this, forwarding_option](const CliArg::Tcp& tcp) {
2✔
601
                return add_tcp_connection(tcp, forwarding_option);
2✔
602
            },
603
            [this, forwarding_option](const CliArg::Serial& serial) {
×
604
                return add_serial_connection(
×
605
                    serial.path, serial.baudrate, serial.flow_control_enabled, forwarding_option);
×
606
            }},
607
        cli_arg.protocol);
86✔
608
}
86✔
609

610
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
611
MavsdkImpl::add_udp_connection(const CliArg::Udp& udp, ForwardingOption forwarding_option)
84✔
612
{
613
    auto new_conn = std::make_unique<UdpConnection>(
84✔
614
        [this](mavlink_message_t& message, Connection* connection) {
2,087✔
615
            receive_message(message, connection);
2,087✔
616
        },
2,087✔
617
        udp.mode == CliArg::Udp::Mode::In ? udp.host : "0.0.0.0",
210✔
618
        udp.mode == CliArg::Udp::Mode::In ? udp.port : 0,
168✔
619
        forwarding_option);
252✔
620

621
    if (!new_conn) {
84✔
622
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
623
    }
624

625
    ConnectionResult ret = new_conn->start();
84✔
626

627
    if (ret != ConnectionResult::Success) {
84✔
628
        return {ret, Mavsdk::ConnectionHandle{}};
×
629
    }
630

631
    if (udp.mode == CliArg::Udp::Mode::Out) {
84✔
632
        // We need to add the IP rather than a hostname, otherwise we end up with two remotes:
633
        // one for the IP, and one for a hostname.
634
        auto remote_ip = resolve_hostname_to_ip(udp.host);
42✔
635

636
        if (!remote_ip) {
42✔
637
            return {ConnectionResult::DestinationIpUnknown, Mavsdk::ConnectionHandle{}};
×
638
        }
639

640
        new_conn->add_remote_to_keep(remote_ip.value(), udp.port);
42✔
641
        std::lock_guard lock(_mutex);
42✔
642

643
        // With a UDP remote, we need to initiate the connection by sending heartbeats.
644
        auto new_configuration = get_configuration();
42✔
645
        new_configuration.set_always_send_heartbeats(true);
42✔
646
        set_configuration(new_configuration);
42✔
647
    }
42✔
648

649
    auto handle = add_connection(std::move(new_conn));
84✔
650

651
    return {ConnectionResult::Success, handle};
84✔
652
}
84✔
653

654
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
655
MavsdkImpl::add_tcp_connection(const CliArg::Tcp& tcp, ForwardingOption forwarding_option)
2✔
656
{
657
    if (tcp.mode == CliArg::Tcp::Mode::Out) {
2✔
658
        auto new_conn = std::make_unique<TcpClientConnection>(
1✔
659
            [this](mavlink_message_t& message, Connection* connection) {
7✔
660
                receive_message(message, connection);
7✔
661
            },
7✔
662
            tcp.host,
1✔
663
            tcp.port,
1✔
664
            forwarding_option);
1✔
665
        if (!new_conn) {
1✔
666
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
667
        }
668
        ConnectionResult ret = new_conn->start();
1✔
669
        if (ret == ConnectionResult::Success) {
1✔
670
            return {ret, add_connection(std::move(new_conn))};
1✔
671
        } else {
672
            return {ret, Mavsdk::ConnectionHandle{}};
×
673
        }
674
    } else {
1✔
675
        auto new_conn = std::make_unique<TcpServerConnection>(
1✔
676
            [this](mavlink_message_t& message, Connection* connection) {
12✔
677
                receive_message(message, connection);
12✔
678
            },
12✔
679
            tcp.host,
1✔
680
            tcp.port,
1✔
681
            forwarding_option);
1✔
682
        if (!new_conn) {
1✔
683
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
684
        }
685
        ConnectionResult ret = new_conn->start();
1✔
686
        if (ret == ConnectionResult::Success) {
1✔
687
            return {ret, add_connection(std::move(new_conn))};
1✔
688
        } else {
689
            return {ret, Mavsdk::ConnectionHandle{}};
×
690
        }
691
    }
1✔
692
}
693

694
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
695
    const std::string& dev_path,
696
    int baudrate,
697
    bool flow_control,
698
    ForwardingOption forwarding_option)
699
{
700
    auto new_conn = std::make_unique<SerialConnection>(
×
701
        [this](mavlink_message_t& message, Connection* connection) {
×
702
            receive_message(message, connection);
×
703
        },
×
704
        dev_path,
705
        baudrate,
706
        flow_control,
707
        forwarding_option);
×
708
    if (!new_conn) {
×
709
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
710
    }
711
    ConnectionResult ret = new_conn->start();
×
712
    if (ret == ConnectionResult::Success) {
×
713
        auto handle = add_connection(std::move(new_conn));
×
714

715
        auto new_configuration = get_configuration();
×
716

717
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
718
        // to initiate the MAVLink connection by sending heartbeats.
719
        // Therefore, we override the default here and enable sending heartbeats.
720
        new_configuration.set_always_send_heartbeats(true);
×
721
        set_configuration(new_configuration);
×
722

723
        return {ret, handle};
×
724

725
    } else {
726
        return {ret, Mavsdk::ConnectionHandle{}};
×
727
    }
728
}
×
729

730
Mavsdk::ConnectionHandle MavsdkImpl::add_connection(std::unique_ptr<Connection>&& new_connection)
86✔
731
{
732
    std::lock_guard lock(_mutex);
86✔
733
    auto handle = _connections_handle_factory.create();
86✔
734
    _connections.emplace_back(ConnectionEntry{std::move(new_connection), handle});
86✔
735

736
    return handle;
172✔
737
}
86✔
738

739
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
×
740
{
741
    std::lock_guard lock(_mutex);
×
742

743
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
×
744
        return (entry.handle == handle);
×
745
    }));
746
}
×
747

748
Mavsdk::Configuration MavsdkImpl::get_configuration() const
42✔
749
{
750
    std::lock_guard configuration_lock(_mutex);
42✔
751
    return _configuration;
84✔
752
}
42✔
753

754
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
129✔
755
{
756
    std::lock_guard server_components_lock(_server_components_mutex);
129✔
757
    // We just point the default to the newly created component. This means
758
    // that the previous default component will be deleted if it is not
759
    // used/referenced anywhere.
760
    _default_server_component =
129✔
761
        server_component_by_id_with_lock(new_configuration.get_component_id());
129✔
762

763
    if (new_configuration.get_always_send_heartbeats() &&
214✔
764
        !_configuration.get_always_send_heartbeats()) {
85✔
765
        start_sending_heartbeats();
43✔
766
    } else if (
86✔
767
        !new_configuration.get_always_send_heartbeats() &&
130✔
768
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
130✔
769
        stop_sending_heartbeats();
×
770
    }
771

772
    _configuration = new_configuration;
129✔
773
    // We cache these values as atomic to avoid having to lock any mutex for them.
774
    _our_system_id = new_configuration.get_system_id();
129✔
775
    _our_component_id = new_configuration.get_component_id();
129✔
776
}
129✔
777

778
uint8_t MavsdkImpl::get_own_system_id() const
5,166✔
779
{
780
    return _our_system_id;
5,166✔
781
}
782

783
uint8_t MavsdkImpl::get_own_component_id() const
1,383✔
784
{
785
    return _our_component_id;
1,383✔
786
}
787

788
uint8_t MavsdkImpl::channel() const
×
789
{
790
    // TODO
791
    return 0;
×
792
}
793

794
Autopilot MavsdkImpl::autopilot() const
×
795
{
796
    // TODO
797
    return Autopilot::Px4;
×
798
}
799

800
// FIXME: this should be per component
801
uint8_t MavsdkImpl::get_mav_type() const
244✔
802
{
803
    return _configuration.get_mav_type();
244✔
804
}
805

806
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
86✔
807
{
808
    // Needs _systems_lock
809

810
    if (_should_exit) {
86✔
811
        // When the system got destroyed in the destructor, we have to give up.
812
        return;
×
813
    }
814

815
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
86✔
816
        LogDebug() << "Initializing connection to remote system...";
×
817
    } else {
818
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
258✔
819
                   << " Comp ID: " << static_cast<int>(comp_id);
258✔
820
    }
821

822
    // Make a system with its first component
823
    auto new_system = std::make_shared<System>(*this);
86✔
824
    new_system->init(system_id, comp_id);
86✔
825

826
    _systems.emplace_back(system_id, new_system);
86✔
827
}
86✔
828

829
void MavsdkImpl::notify_on_discover()
86✔
830
{
831
    // Queue the callbacks without holding the mutex to avoid deadlocks
832
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
129✔
833
}
86✔
834

835
void MavsdkImpl::notify_on_timeout()
×
836
{
837
    // Queue the callbacks without holding the mutex to avoid deadlocks
838
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
839
}
×
840

841
Mavsdk::NewSystemHandle
842
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
43✔
843
{
844
    std::lock_guard lock(_mutex);
43✔
845

846
    const auto handle = _new_system_callbacks.subscribe(callback);
43✔
847

848
    if (is_any_system_connected()) {
43✔
849
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
850
    }
851

852
    return handle;
86✔
853
}
43✔
854

855
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
42✔
856
{
857
    _new_system_callbacks.unsubscribe(handle);
42✔
858
}
42✔
859

860
bool MavsdkImpl::is_any_system_connected() const
43✔
861
{
862
    std::vector<std::shared_ptr<System>> connected_systems = systems();
43✔
863
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
43✔
864
        return system->is_connected();
×
865
    });
43✔
866
}
43✔
867

868
void MavsdkImpl::work_thread()
87✔
869
{
870
    while (!_should_exit) {
20,213✔
871
        // Process incoming messages
872
        process_messages();
19,621✔
873

874
        // Run timers
875
        timeout_handler.run_once();
20,366✔
876
        call_every_handler.run_once();
20,088✔
877

878
        // Do component work
879
        {
880
            std::lock_guard lock(_server_components_mutex);
20,349✔
881
            for (auto& it : _server_components) {
40,400✔
882
                if (it.second != nullptr) {
20,361✔
883
                    it.second->_impl->do_work();
19,813✔
884
                }
885
            }
886
        }
19,405✔
887

888
        // Deliver outgoing messages
889
        deliver_messages();
19,703✔
890

891
        // If no messages to send, check if there are messages to receive
892
        std::unique_lock lock_received(_received_messages_mutex);
19,897✔
893
        if (_received_messages.empty()) {
19,689✔
894
            // No messages to process, wait for a signal or timeout
895
            _received_messages_cv.wait_for(lock_received, std::chrono::milliseconds(10), [this]() {
19,449✔
896
                return !_received_messages.empty() || _should_exit;
39,784✔
897
            });
898
        }
899
    }
19,926✔
900
}
429✔
901

902
void MavsdkImpl::call_user_callback_located(
1,046✔
903
    const std::string& filename, const int linenumber, const std::function<void()>& func)
904
{
905
    // Don't enqueue callbacks if we're shutting down
906
    if (_should_exit) {
1,046✔
907
        return;
×
908
    }
909

910
    auto callback_size = _user_callback_queue.size();
1,046✔
911
    if (callback_size == 10) {
1,046✔
912
        LogWarn()
×
913
            << "User callback queue too slow.\n"
×
914
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
915

916
    } else if (callback_size == 99) {
1,046✔
917
        LogErr()
×
918
            << "User callback queue overflown\n"
×
919
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
920

921
    } else if (callback_size == 100) {
1,046✔
922
        return;
×
923
    }
924

925
    // We only need to keep track of filename and linenumber if we're actually debugging this.
926
    UserCallback user_callback =
1,046✔
927
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
2,092✔
928

929
    _user_callback_queue.push_back(std::make_shared<UserCallback>(user_callback));
1,046✔
930
}
1,046✔
931

932
void MavsdkImpl::process_user_callbacks_thread()
87✔
933
{
934
    while (!_should_exit) {
1,220✔
935
        std::shared_ptr<UserCallback> callback;
1,133✔
936
        {
937
            LockedQueue<UserCallback>::Guard guard(_user_callback_queue);
1,133✔
938
            callback = guard.wait_and_pop_front();
1,133✔
939
        }
1,133✔
940

941
        if (!callback) {
1,133✔
942
            continue;
87✔
943
        }
944

945
        // Check if we're in the process of shutting down before executing the callback
946
        if (_should_exit) {
1,046✔
947
            continue;
×
948
        }
949

950
        const double timeout_s = 1.0;
1,046✔
951
        auto cookie = timeout_handler.add(
1,046✔
952
            [&]() {
×
953
                if (_callback_debugging) {
×
954
                    LogWarn() << "Callback called from " << callback->filename << ":"
×
955
                              << callback->linenumber << " took more than " << timeout_s
×
956
                              << " second to run.";
×
957
                    fflush(stdout);
×
958
                    fflush(stderr);
×
959
                    abort();
×
960
                } else {
961
                    LogWarn()
×
962
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
963
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
964
                }
965
            },
×
966
            timeout_s);
1,046✔
967
        callback->func();
1,046✔
968
        timeout_handler.remove(cookie);
1,046✔
969
    }
1,133✔
970
}
87✔
971

972
void MavsdkImpl::start_sending_heartbeats()
215✔
973
{
974
    // Check if we're in the process of shutting down
975
    if (_should_exit) {
215✔
976
        return;
×
977
    }
978

979
    // Before sending out first heartbeats we need to make sure we have a
980
    // default server component.
981
    default_server_component_impl();
215✔
982

983
    {
984
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
215✔
985
        call_every_handler.remove(_heartbeat_send_cookie);
215✔
986
        _heartbeat_send_cookie =
430✔
987
            call_every_handler.add([this]() { send_heartbeats(); }, HEARTBEAT_SEND_INTERVAL_S);
457✔
988
    }
215✔
989
}
990

991
void MavsdkImpl::stop_sending_heartbeats()
×
992
{
993
    if (!_configuration.get_always_send_heartbeats()) {
×
994
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
×
995
        call_every_handler.remove(_heartbeat_send_cookie);
×
996
    }
×
997
}
×
998

999
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
1,071✔
1000
{
1001
    std::lock_guard lock(_server_components_mutex);
1,071✔
1002
    return default_server_component_with_lock();
1,071✔
1003
}
1,071✔
1004

1005
ServerComponentImpl& MavsdkImpl::default_server_component_with_lock()
1,071✔
1006
{
1007
    if (_default_server_component == nullptr) {
1,071✔
1008
        _default_server_component = server_component_by_id_with_lock(_our_component_id);
×
1009
    }
1010
    return *_default_server_component->_impl;
1,071✔
1011
}
1012

1013
void MavsdkImpl::send_heartbeats()
242✔
1014
{
1015
    std::lock_guard lock(_server_components_mutex);
242✔
1016

1017
    for (auto& it : _server_components) {
486✔
1018
        if (it.second != nullptr) {
244✔
1019
            it.second->_impl->send_heartbeat();
243✔
1020
        }
1021
    }
1022
}
241✔
1023

1024
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
22✔
1025
{
1026
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
22✔
1027
    _intercept_incoming_messages_callback = callback;
22✔
1028
}
22✔
1029

1030
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
1031
{
1032
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
14✔
1033
    _intercept_outgoing_messages_callback = callback;
14✔
1034
}
14✔
1035

1036
Mavsdk::ConnectionErrorHandle
1037
MavsdkImpl::subscribe_connection_errors(Mavsdk::ConnectionErrorCallback callback)
×
1038
{
1039
    std::lock_guard lock(_mutex);
×
1040

1041
    const auto handle = _connections_errors_subscriptions.subscribe(callback);
×
1042

1043
    return handle;
×
1044
}
×
1045

1046
void MavsdkImpl::unsubscribe_connection_errors(Mavsdk::ConnectionErrorHandle handle)
×
1047
{
1048
    std::lock_guard lock(_mutex);
×
1049
    _connections_errors_subscriptions.unsubscribe(handle);
×
1050
}
×
1051

1052
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
2,106✔
1053
{
1054
    // Checks whether connection knows target system ID by extracting target system if set.
1055
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
2,106✔
1056

1057
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
2,105✔
1058
        return 0;
382✔
1059
    }
1060

1061
    // Don't look at the target system offset if it is outside the payload length.
1062
    // This can happen if the fields are trimmed.
1063
    if (meta->target_system_ofs >= message.len) {
1,723✔
1064
        return 0;
5✔
1065
    }
1066

1067
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,718✔
1068
}
1069

1070
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
×
1071
{
1072
    // Checks whether connection knows target system ID by extracting target system if set.
1073
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
×
1074

1075
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
×
1076
        return 0;
×
1077
    }
1078

1079
    // Don't look at the target component offset if it is outside the payload length.
1080
    // This can happen if the fields are trimmed.
1081
    if (meta->target_component_ofs >= message.len) {
×
1082
        return 0;
×
1083
    }
1084

1085
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
×
1086
}
1087

1088
Sender& MavsdkImpl::sender()
×
1089
{
1090
    std::lock_guard lock(_server_components_mutex);
×
1091
    return default_server_component_with_lock().sender();
×
1092
}
×
1093

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