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

mavlink / MAVSDK / 14787393159

02 May 2025 02:22AM UTC coverage: 44.322% (+0.1%) from 44.223%
14787393159

Pull #2542

github

web-flow
Merge 0228013e3 into 2cf24f244
Pull Request #2542: Fixing thread sanitizer issues

221 of 312 new or added lines in 17 files covered. (70.83%)

75 existing lines in 7 files now uncovered.

14742 of 33261 relevant lines covered (44.32%)

280.93 hits per line

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

58.96
/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 "plugin_base.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
    _work_thread = new std::thread(&MavsdkImpl::work_thread, this);
87✔
56

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

61
MavsdkImpl::~MavsdkImpl()
87✔
62
{
63
    _should_exit = true;
87✔
64

65
    if (_process_user_callbacks_thread != nullptr) {
87✔
66
        _user_callback_queue.stop();
87✔
67
        _process_user_callbacks_thread->join();
87✔
68
        delete _process_user_callbacks_thread;
87✔
69
        _process_user_callbacks_thread = nullptr;
87✔
70
    }
71

72
    if (_work_thread != nullptr) {
87✔
73
        _work_thread->join();
87✔
74
        delete _work_thread;
87✔
75
        _work_thread = nullptr;
87✔
76
    }
77

78
    {
79
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
87✔
80
        _systems.clear();
87✔
81
    }
87✔
82

83
    {
84
        std::lock_guard<std::mutex> lock(_connections_mutex);
87✔
85
        _connections.clear();
87✔
86
    }
87✔
87
}
87✔
88

89
std::string MavsdkImpl::version()
1✔
90
{
91
    static unsigned version_counter = 0;
92

93
    ++version_counter;
1✔
94

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

117
std::vector<std::shared_ptr<System>> MavsdkImpl::systems() const
86✔
118
{
119
    std::vector<std::shared_ptr<System>> systems_result{};
86✔
120

121
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
86✔
122
    for (auto& system : _systems) {
129✔
123
        // We ignore the 0 entry because it's just a null system.
124
        // It's only created because the older, deprecated API needs a
125
        // reference.
126
        if (system.first == 0) {
43✔
127
            continue;
×
128
        }
129
        systems_result.push_back(system.second);
43✔
130
    }
131

132
    return systems_result;
86✔
133
}
86✔
134

135
std::optional<std::shared_ptr<System>> MavsdkImpl::first_autopilot(double timeout_s)
33✔
136
{
137
    {
138
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
33✔
139
        for (auto system : _systems) {
33✔
UNCOV
140
            if (system.second->is_connected() && system.second->has_autopilot()) {
×
141
                return system.second;
×
142
            }
UNCOV
143
        }
×
144
    }
33✔
145

146
    if (timeout_s == 0.0) {
33✔
147
        // Don't wait at all.
148
        return {};
×
149
    }
150

151
    auto prom = std::promise<std::shared_ptr<System>>();
33✔
152

153
    std::once_flag flag;
33✔
154
    auto handle = subscribe_on_new_system([this, &prom, &flag]() {
66✔
155
        const auto system = systems().at(0);
66✔
156
        if (system->is_connected() && system->has_autopilot()) {
33✔
157
            std::call_once(flag, [&prom, &system]() { prom.set_value(system); });
66✔
158
        }
159
    });
66✔
160

161
    auto fut = prom.get_future();
33✔
162

163
    if (timeout_s > 0.0) {
33✔
164
        if (fut.wait_for(std::chrono::milliseconds(int64_t(timeout_s * 1e3))) ==
33✔
165
            std::future_status::ready) {
166
            unsubscribe_on_new_system(handle);
33✔
167
            return fut.get();
33✔
168

169
        } else {
170
            unsubscribe_on_new_system(handle);
×
171
            return std::nullopt;
×
172
        }
173
    } else {
174
        fut.wait();
×
175
        unsubscribe_on_new_system(handle);
×
176
        return std::optional(fut.get());
×
177
    }
178
}
33✔
179

180
std::shared_ptr<ServerComponent> MavsdkImpl::server_component(unsigned instance)
47✔
181
{
182
    auto component_type = _configuration.get_component_type();
47✔
183
    switch (component_type) {
47✔
184
        case ComponentType::Autopilot:
47✔
185
        case ComponentType::GroundStation:
186
        case ComponentType::CompanionComputer:
187
        case ComponentType::Camera:
188
        case ComponentType::Gimbal:
189
        case ComponentType::RemoteId:
190
        case ComponentType::Custom:
191
            return server_component_by_type(component_type, instance);
47✔
192
        default:
×
193
            LogErr() << "Unknown component type";
×
194
            return {};
×
195
    }
196
}
197

198
std::shared_ptr<ServerComponent>
199
MavsdkImpl::server_component_by_type(ComponentType server_component_type, unsigned instance)
47✔
200
{
201
    switch (server_component_type) {
47✔
202
        case ComponentType::Autopilot:
33✔
203
            if (instance == 0) {
33✔
204
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1);
33✔
205
            } else {
206
                LogErr() << "Only autopilot instance 0 is valid";
×
207
                return {};
×
208
            }
209

210
        case ComponentType::GroundStation:
×
211
            if (instance == 0) {
×
212
                return server_component_by_id(MAV_COMP_ID_MISSIONPLANNER);
×
213
            } else {
214
                LogErr() << "Only one ground station supported at this time";
×
215
                return {};
×
216
            }
217

218
        case ComponentType::CompanionComputer:
1✔
219
            if (instance == 0) {
1✔
220
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER);
1✔
221
            } else if (instance == 1) {
×
222
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER2);
×
223
            } else if (instance == 2) {
×
224
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER3);
×
225
            } else if (instance == 3) {
×
226
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER4);
×
227
            } else {
228
                LogErr() << "Only companion computer 0..3 are supported";
×
229
                return {};
×
230
            }
231

232
        case ComponentType::Camera:
13✔
233
            if (instance == 0) {
13✔
234
                return server_component_by_id(MAV_COMP_ID_CAMERA);
13✔
235
            } else if (instance == 1) {
×
236
                return server_component_by_id(MAV_COMP_ID_CAMERA2);
×
237
            } else if (instance == 2) {
×
238
                return server_component_by_id(MAV_COMP_ID_CAMERA3);
×
239
            } else if (instance == 3) {
×
240
                return server_component_by_id(MAV_COMP_ID_CAMERA4);
×
241
            } else if (instance == 4) {
×
242
                return server_component_by_id(MAV_COMP_ID_CAMERA5);
×
243
            } else if (instance == 5) {
×
244
                return server_component_by_id(MAV_COMP_ID_CAMERA6);
×
245
            } else {
246
                LogErr() << "Only camera 0..5 are supported";
×
247
                return {};
×
248
            }
249

250
        default:
×
251
            LogErr() << "Unknown server component type";
×
252
            return {};
×
253
    }
254
}
255

256
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id(uint8_t component_id)
176✔
257
{
258
    if (component_id == 0) {
176✔
259
        LogErr() << "Server component with component ID 0 not allowed";
×
260
        return nullptr;
×
261
    }
262

263
    std::lock_guard<std::mutex> lock(_server_components_mutex);
176✔
264

265
    for (auto& it : _server_components) {
177✔
266
        if (it.first == component_id) {
89✔
267
            if (it.second != nullptr) {
88✔
268
                return it.second;
88✔
269
            } else {
270
                it.second = std::make_shared<ServerComponent>(*this, component_id);
×
271
            }
272
        }
273
    }
274

275
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
176✔
276
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
176✔
277

278
    return _server_components.back().second;
88✔
279
}
176✔
280

281
void MavsdkImpl::forward_message(mavlink_message_t& message, Connection* connection)
×
282
{
283
    // Forward_message Function implementing Mavlink routing rules.
284
    // See https://mavlink.io/en/guide/routing.html
285

286
    bool forward_heartbeats_enabled = true;
×
287
    const uint8_t target_system_id = get_target_system_id(message);
×
288
    const uint8_t target_component_id = get_target_component_id(message);
×
289

290
    // If it's a message only for us, we keep it, otherwise, we forward it.
291
    const bool targeted_only_at_us =
292
        (target_system_id == get_own_system_id() && target_component_id == get_own_component_id());
×
293

294
    // We don't forward heartbeats unless it's specifically enabled.
295
    const bool heartbeat_check_ok =
×
296
        (message.msgid != MAVLINK_MSG_ID_HEARTBEAT || forward_heartbeats_enabled);
×
297

298
    if (!targeted_only_at_us && heartbeat_check_ok) {
×
299
        unsigned successful_emissions = 0;
×
300
        for (auto& entry : _connections) {
×
301
            // Check whether the connection is not the one from which we received the message.
302
            // And also check if the connection was set to forward messages.
303
            if (entry.connection.get() == connection ||
×
304
                !entry.connection->should_forward_messages()) {
×
305
                continue;
×
306
            }
307
            auto result = (*entry.connection).send_message(message);
×
308
            if (result.first) {
×
309
                successful_emissions++;
×
310
            } else {
311
                _connections_errors_subscriptions.queue(
×
312
                    Mavsdk::ConnectionError{result.second, entry.handle},
×
313
                    [this](const auto& func) { call_user_callback(func); });
×
314
            }
315
        }
×
316
        if (successful_emissions == 0) {
×
317
            LogErr() << "Message forwarding failed";
×
318
        }
319
    }
320
}
×
321

322
void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connection)
1,914✔
323
{
324
    if (_message_logging_on) {
1,914✔
325
        LogDebug() << "Processing message " << message.msgid << " from "
×
326
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
327
    }
328

329
    if (_should_exit) {
1,914✔
330
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
331
        return;
11✔
332
    }
333

334
    // This is a low level interface where incoming messages can be tampered
335
    // with or even dropped.
336
    {
337
        std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
1,902✔
338
        if (_intercept_incoming_messages_callback != nullptr) {
1,900✔
339
            bool keep = _intercept_incoming_messages_callback(message);
245✔
340
            if (!keep) {
245✔
341
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
38✔
342
                return;
40✔
343
            }
344
        }
345
    }
1,902✔
346

347
    if (_should_exit) {
1,862✔
348
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
349
        return;
×
350
    }
351

352
    /** @note: Forward message if option is enabled and multiple interfaces are connected.
353
     *  Performs message forwarding checks for every messages if message forwarding
354
     *  is enabled on at least one connection, and in case of a single forwarding connection,
355
     *  we check that it is not the one which received the current message.
356
     *
357
     * Conditions:
358
     * 1. At least 2 connections.
359
     * 2. At least 1 forwarding connection.
360
     * 3. At least 2 forwarding connections or current connection is not forwarding.
361
     */
362

363
    {
364
        std::lock_guard<std::mutex> lock(_connections_mutex);
1,862✔
365

366
        if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
1,863✔
367
            (mavsdk::Connection::forwarding_connections_count() > 1 ||
×
UNCOV
368
             !connection->should_forward_messages())) {
×
369
            if (_message_logging_on) {
×
370
                LogDebug() << "Forwarding message " << message.msgid << " from "
×
371
                           << static_cast<int>(message.sysid) << "/"
×
372
                           << static_cast<int>(message.compid);
×
373
            }
374
            forward_message(message, connection);
×
375
        }
376
    }
1,863✔
377

378
    // Don't ever create a system with sysid 0.
379
    if (message.sysid == 0) {
1,862✔
380
        if (_message_logging_on) {
×
381
            LogDebug() << "Ignoring message with sysid == 0";
×
382
        }
383
        return;
×
384
    }
385

386
    // Filter out messages by QGroundControl, however, only do that if MAVSDK
387
    // is also implementing a ground station and not if it is used in another
388
    // configuration, e.g. on a companion.
389
    //
390
    // This is a workaround because PX4 started forwarding messages between
391
    // mavlink instances which leads to existing implementations (including
392
    // examples and integration tests) to connect to QGroundControl by accident
393
    // instead of PX4 because the check `has_autopilot()` is not used.
394
    if (_configuration.get_component_type() == ComponentType::GroundStation &&
1,862✔
395
        message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
1,862✔
396
        if (_message_logging_on) {
×
397
            LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
398
        }
399
        return;
×
400
    }
401

402
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
1,862✔
403

404
    bool found_system = false;
1,862✔
405
    for (auto& system : _systems) {
1,860✔
406
        if (system.first == message.sysid) {
1,775✔
407
            system.second->system_impl()->add_new_component(message.compid);
1,777✔
408
            found_system = true;
1,776✔
409
            break;
1,776✔
410
        }
411
    }
412

413
    if (!found_system) {
1,860✔
414
        if (_system_debugging) {
86✔
415
            LogWarn() << "Create new system/component " << (int)message.sysid << "/"
×
416
                      << (int)message.compid;
×
417
            LogWarn() << "From message " << (int)message.msgid << " with len " << (int)message.len;
×
418
            std::string bytes = "";
×
419
            for (unsigned i = 0; i < 12 + message.len; ++i) {
×
420
                bytes += std::to_string(reinterpret_cast<uint8_t*>(&message)[i]) + ' ';
×
421
            }
422
            LogWarn() << "Bytes: " << bytes;
×
423
        }
×
424
        make_system_with_component(message.sysid, message.compid);
86✔
425
    }
426

427
    if (_should_exit) {
1,860✔
428
        // Don't try to call at() if systems have already been destroyed
429
        // in destructor.
430
        return;
×
431
    }
432

433
    mavlink_message_handler.process_message(message);
1,859✔
434

435
    for (auto& system : _systems) {
1,862✔
436
        if (system.first == message.sysid) {
1,862✔
437
            system.second->system_impl()->process_mavlink_message(message);
1,863✔
438
            break;
1,863✔
439
        }
440
    }
441
}
1,863✔
442

443
bool MavsdkImpl::send_message(mavlink_message_t& message)
2,038✔
444
{
445
    if (_message_logging_on) {
2,038✔
446
        LogDebug() << "Sending message " << message.msgid << " from "
×
447
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid)
×
448
                   << " to " << static_cast<int>(get_target_system_id(message)) << "/"
×
449
                   << static_cast<int>(get_target_component_id(message));
×
450
    }
451

452
    // This is a low level interface where outgoing messages can be tampered
453
    // with or even dropped.
454
    if (_intercept_outgoing_messages_callback != nullptr) {
2,038✔
455
        const bool keep = _intercept_outgoing_messages_callback(message);
221✔
456
        if (!keep) {
221✔
457
            // We fake that everything was sent as instructed because
458
            // a potential loss would happen later, and we would not be informed
459
            // about it.
460
            LogDebug() << "Dropped outgoing message: " << int(message.msgid);
81✔
461
            return true;
81✔
462
        }
463
    }
464

465
    std::lock_guard<std::mutex> lock(_connections_mutex);
1,956✔
466

467
    if (_connections.empty()) {
1,957✔
468
        // We obviously can't send any messages without a connection added, so
469
        // we silently ignore this.
470
        return true;
43✔
471
    }
472

473
    uint8_t successful_emissions = 0;
1,913✔
474
    for (auto& _connection : _connections) {
3,827✔
475
        const uint8_t target_system_id = get_target_system_id(message);
1,914✔
476

477
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
1,913✔
478
            continue;
×
479
        }
480
        const auto result = (*_connection.connection).send_message(message);
1,911✔
481
        if (result.first) {
1,914✔
482
            successful_emissions++;
1,914✔
483
        } else {
484
            _connections_errors_subscriptions.queue(
×
485
                Mavsdk::ConnectionError{result.second, _connection.handle},
×
486
                [this](const auto& func) { call_user_callback(func); });
×
487
        }
488
    }
1,914✔
489

490
    if (successful_emissions == 0) {
1,913✔
491
        LogErr() << "Sending message failed";
×
492
        return false;
×
493
    }
494

495
    return true;
1,913✔
496
}
1,956✔
497

498
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
86✔
499
    const std::string& connection_url, ForwardingOption forwarding_option)
500
{
501
    CliArg cli_arg;
86✔
502
    if (!cli_arg.parse(connection_url)) {
86✔
503
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
504
    }
505

506
    return std::visit(
86✔
507
        overloaded{
172✔
508
            [](std::monostate) {
×
509
                // Should not happen anyway.
510
                return std::pair<ConnectionResult, Mavsdk::ConnectionHandle>{
×
511
                    ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle()};
×
512
            },
513
            [this, forwarding_option](const CliArg::Udp& udp) {
84✔
514
                return add_udp_connection(udp, forwarding_option);
84✔
515
            },
516
            [this, forwarding_option](const CliArg::Tcp& tcp) {
2✔
517
                return add_tcp_connection(tcp, forwarding_option);
2✔
518
            },
519
            [this, forwarding_option](const CliArg::Serial& serial) {
×
520
                return add_serial_connection(
×
521
                    serial.path, serial.baudrate, serial.flow_control_enabled, forwarding_option);
×
522
            }},
523
        cli_arg.protocol);
86✔
524
}
86✔
525

526
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
527
MavsdkImpl::add_udp_connection(const CliArg::Udp& udp, ForwardingOption forwarding_option)
84✔
528
{
529
    auto new_conn = std::make_unique<UdpConnection>(
84✔
530
        [this](mavlink_message_t& message, Connection* connection) {
1,902✔
531
            receive_message(message, connection);
1,902✔
532
        },
1,904✔
533
        udp.mode == CliArg::Udp::Mode::In ? udp.host : "0.0.0.0",
210✔
534
        udp.mode == CliArg::Udp::Mode::In ? udp.port : 0,
168✔
535
        forwarding_option);
252✔
536

537
    if (!new_conn) {
84✔
538
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
539
    }
540

541
    ConnectionResult ret = new_conn->start();
84✔
542

543
    if (ret != ConnectionResult::Success) {
84✔
544
        return {ret, Mavsdk::ConnectionHandle{}};
×
545
    }
546

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

552
        if (!remote_ip) {
42✔
553
            return {ConnectionResult::DestinationIpUnknown, Mavsdk::ConnectionHandle{}};
×
554
        }
555

556
        new_conn->add_remote(remote_ip.value(), udp.port);
42✔
557
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
42✔
558

559
        // With a UDP remote, we need to initiate the connection by sending heartbeats.
560
        auto new_configuration = get_configuration();
42✔
561
        new_configuration.set_always_send_heartbeats(true);
42✔
562
        set_configuration(new_configuration);
42✔
563
    }
42✔
564

565
    auto handle = add_connection(std::move(new_conn));
84✔
566

567
    return {ConnectionResult::Success, handle};
84✔
568
}
84✔
569

570
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
571
MavsdkImpl::add_tcp_connection(const CliArg::Tcp& tcp, ForwardingOption forwarding_option)
2✔
572
{
573
    if (tcp.mode == CliArg::Tcp::Mode::Out) {
2✔
574
        auto new_conn = std::make_unique<TcpClientConnection>(
1✔
575
            [this](mavlink_message_t& message, Connection* connection) {
3✔
576
                receive_message(message, connection);
3✔
577
            },
3✔
578
            tcp.host,
1✔
579
            tcp.port,
1✔
580
            forwarding_option);
1✔
581
        if (!new_conn) {
1✔
582
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
583
        }
584
        ConnectionResult ret = new_conn->start();
1✔
585
        if (ret == ConnectionResult::Success) {
1✔
586
            return {ret, add_connection(std::move(new_conn))};
1✔
587
        } else {
588
            return {ret, Mavsdk::ConnectionHandle{}};
×
589
        }
590
    } else {
1✔
591
        auto new_conn = std::make_unique<TcpServerConnection>(
1✔
592
            [this](mavlink_message_t& message, Connection* connection) {
7✔
593
                receive_message(message, connection);
7✔
594
            },
7✔
595
            tcp.host,
1✔
596
            tcp.port,
1✔
597
            forwarding_option);
1✔
598
        if (!new_conn) {
1✔
599
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
600
        }
601
        ConnectionResult ret = new_conn->start();
1✔
602
        if (ret == ConnectionResult::Success) {
1✔
603
            return {ret, add_connection(std::move(new_conn))};
1✔
604
        } else {
605
            return {ret, Mavsdk::ConnectionHandle{}};
×
606
        }
607
    }
1✔
608
}
609

610
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
611
    const std::string& dev_path,
612
    int baudrate,
613
    bool flow_control,
614
    ForwardingOption forwarding_option)
615
{
NEW
616
    auto new_conn = std::make_unique<SerialConnection>(
×
617
        [this](mavlink_message_t& message, Connection* connection) {
×
618
            receive_message(message, connection);
×
619
        },
×
620
        dev_path,
621
        baudrate,
622
        flow_control,
623
        forwarding_option);
×
624
    if (!new_conn) {
×
625
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
626
    }
627
    ConnectionResult ret = new_conn->start();
×
628
    if (ret == ConnectionResult::Success) {
×
NEW
629
        auto handle = add_connection(std::move(new_conn));
×
630

631
        auto new_configuration = get_configuration();
×
632

633
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
634
        // to initiate the MAVLink connection by sending heartbeats.
635
        // Therefore, we override the default here and enable sending heartbeats.
636
        new_configuration.set_always_send_heartbeats(true);
×
637
        set_configuration(new_configuration);
×
638

639
        return {ret, handle};
×
640

641
    } else {
642
        return {ret, Mavsdk::ConnectionHandle{}};
×
643
    }
644
}
×
645

646
Mavsdk::ConnectionHandle MavsdkImpl::add_connection(std::unique_ptr<Connection>&& new_connection)
86✔
647
{
648
    std::lock_guard<std::mutex> lock(_connections_mutex);
86✔
649
    auto handle = _connections_handle_factory.create();
86✔
650
    _connections.emplace_back(ConnectionEntry{std::move(new_connection), handle});
86✔
651

652
    return handle;
172✔
653
}
86✔
654

655
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
×
656
{
657
    std::lock_guard<std::mutex> lock(_connections_mutex);
×
658

659
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
×
660
        return (entry.handle == handle);
×
661
    }));
662
}
×
663

664
Mavsdk::Configuration MavsdkImpl::get_configuration() const
42✔
665
{
666
    return _configuration;
42✔
667
}
668

669
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
129✔
670
{
671
    // We just point the default to the newly created component. This means
672
    // that the previous default component will be deleted if it is not
673
    // used/referenced anywhere.
674
    _default_server_component = server_component_by_id(new_configuration.get_component_id());
129✔
675

676
    if (new_configuration.get_always_send_heartbeats() &&
214✔
677
        !_configuration.get_always_send_heartbeats()) {
85✔
678
        start_sending_heartbeats();
43✔
679
    } else if (
86✔
680
        !new_configuration.get_always_send_heartbeats() &&
130✔
681
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
130✔
682
        stop_sending_heartbeats();
×
683
    }
684

685
    _configuration = new_configuration;
129✔
686
}
129✔
687

688
uint8_t MavsdkImpl::get_own_system_id() const
4,878✔
689
{
690
    return _configuration.get_system_id();
4,878✔
691
}
692

693
uint8_t MavsdkImpl::get_own_component_id() const
1,283✔
694
{
695
    return _configuration.get_component_id();
1,283✔
696
}
697

698
uint8_t MavsdkImpl::channel() const
×
699
{
700
    // TODO
701
    return 0;
×
702
}
703

704
Autopilot MavsdkImpl::autopilot() const
×
705
{
706
    // TODO
707
    return Autopilot::Px4;
×
708
}
709

710
// FIXME: this should be per component
711
uint8_t MavsdkImpl::get_mav_type() const
257✔
712
{
713
    return _configuration.get_mav_type();
257✔
714
}
715

716
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
86✔
717
{
718
    // Needs _systems_lock
719

720
    if (_should_exit) {
86✔
721
        // When the system got destroyed in the destructor, we have to give up.
722
        return;
×
723
    }
724

725
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
86✔
726
        LogDebug() << "Initializing connection to remote system...";
×
727
    } else {
728
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
258✔
729
                   << " Comp ID: " << static_cast<int>(comp_id);
258✔
730
    }
731

732
    // Make a system with its first component
733
    auto new_system = std::make_shared<System>(*this);
86✔
734
    new_system->init(system_id, comp_id);
86✔
735

736
    _systems.emplace_back(system_id, new_system);
86✔
737
}
86✔
738

739
void MavsdkImpl::notify_on_discover()
86✔
740
{
741
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
86✔
742
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
129✔
743
}
86✔
744

745
void MavsdkImpl::notify_on_timeout()
×
746
{
747
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
×
748
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
749
}
×
750

751
Mavsdk::NewSystemHandle
752
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
43✔
753
{
754
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
43✔
755

756
    const auto handle = _new_system_callbacks.subscribe(callback);
43✔
757

758
    if (is_any_system_connected()) {
43✔
759
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
760
    }
761

762
    return handle;
86✔
763
}
43✔
764

765
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
42✔
766
{
767
    _new_system_callbacks.unsubscribe(handle);
42✔
768
}
42✔
769

770
bool MavsdkImpl::is_any_system_connected() const
43✔
771
{
772
    std::vector<std::shared_ptr<System>> connected_systems = systems();
43✔
773
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
43✔
UNCOV
774
        return system->is_connected();
×
775
    });
43✔
776
}
43✔
777

778
void MavsdkImpl::work_thread()
87✔
779
{
780
    while (!_should_exit) {
21,377✔
781
        timeout_handler.run_once();
20,890✔
782
        call_every_handler.run_once();
21,314✔
783

784
        {
785
            std::lock_guard<std::mutex> lock(_server_components_mutex);
21,330✔
786
            for (auto& it : _server_components) {
42,460✔
787
                if (it.second != nullptr) {
21,241✔
788
                    it.second->_impl->do_work();
20,712✔
789
                }
790
            }
791
        }
20,484✔
792

793
        std::this_thread::sleep_for(std::chrono::milliseconds(10));
20,824✔
794
    }
795
}
796

797
void MavsdkImpl::call_user_callback_located(
938✔
798
    const std::string& filename, const int linenumber, const std::function<void()>& func)
799
{
800
    auto callback_size = _user_callback_queue.size();
938✔
801
    if (callback_size == 10) {
938✔
UNCOV
802
        LogWarn()
×
UNCOV
803
            << "User callback queue too slow.\n"
×
UNCOV
804
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
805

806
    } else if (callback_size == 99) {
938✔
807
        LogErr()
×
808
            << "User callback queue overflown\n"
×
809
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
810

811
    } else if (callback_size == 100) {
938✔
812
        return;
×
813
    }
814

815
    // We only need to keep track of filename and linenumber if we're actually debugging this.
816
    UserCallback user_callback =
938✔
817
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
1,876✔
818

819
    _user_callback_queue.enqueue(user_callback);
938✔
820
}
938✔
821

822
void MavsdkImpl::process_user_callbacks_thread()
87✔
823
{
824
    while (!_should_exit) {
1,112✔
825
        auto callback = _user_callback_queue.dequeue();
1,025✔
826
        if (!callback) {
1,025✔
827
            continue;
87✔
828
        }
829

830
        const double timeout_s = 1.0;
938✔
831
        auto cookie = timeout_handler.add(
938✔
832
            [&]() {
×
833
                if (_callback_debugging) {
×
834
                    LogWarn() << "Callback called from " << callback.value().filename << ":"
×
835
                              << callback.value().linenumber << " took more than " << timeout_s
×
836
                              << " second to run.";
×
837
                    fflush(stdout);
×
838
                    fflush(stderr);
×
839
                    abort();
×
840
                } else {
841
                    LogWarn()
×
842
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
843
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
844
                }
845
            },
×
846
            timeout_s);
938✔
847
        callback.value().func();
938✔
848
        timeout_handler.remove(cookie);
938✔
849
    }
1,025✔
850
}
87✔
851

852
void MavsdkImpl::start_sending_heartbeats()
129✔
853
{
854
    // Before sending out first heartbeats we need to make sure we have a
855
    // default server component.
856
    default_server_component_impl();
129✔
857

858
    call_every_handler.remove(_heartbeat_send_cookie);
129✔
859
    _heartbeat_send_cookie =
258✔
860
        call_every_handler.add([this]() { send_heartbeat(); }, HEARTBEAT_SEND_INTERVAL_S);
385✔
861
}
129✔
862

863
void MavsdkImpl::stop_sending_heartbeats()
×
864
{
865
    if (!_configuration.get_always_send_heartbeats()) {
×
866
        call_every_handler.remove(_heartbeat_send_cookie);
×
867
    }
868
}
×
869

870
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
898✔
871
{
872
    if (_default_server_component == nullptr) {
898✔
873
        _default_server_component = server_component_by_id(_configuration.get_component_id());
×
874
    }
875
    return *_default_server_component->_impl;
898✔
876
}
877

878
void MavsdkImpl::send_heartbeat()
254✔
879
{
880
    std::lock_guard<std::mutex> lock(_server_components_mutex);
254✔
881

882
    for (auto& it : _server_components) {
512✔
883
        if (it.second != nullptr) {
255✔
884
            it.second->_impl->send_heartbeat();
254✔
885
        }
886
    }
887
}
256✔
888

889
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
22✔
890
{
891
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
22✔
892
    _intercept_incoming_messages_callback = callback;
22✔
893
}
22✔
894

895
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
896
{
897
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
14✔
898
    _intercept_outgoing_messages_callback = callback;
14✔
899
}
14✔
900

901
Mavsdk::ConnectionErrorHandle
902
MavsdkImpl::subscribe_connection_errors(Mavsdk::ConnectionErrorCallback callback)
×
903
{
904
    std::lock_guard lock(_connections_mutex);
×
905

906
    const auto handle = _connections_errors_subscriptions.subscribe(callback);
×
907

908
    return handle;
×
909
}
×
910

911
void MavsdkImpl::unsubscribe_connection_errors(Mavsdk::ConnectionErrorHandle handle)
×
912
{
913
    std::lock_guard lock(_connections_mutex);
×
914
    _connections_errors_subscriptions.unsubscribe(handle);
×
915
}
×
916

917
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
1,914✔
918
{
919
    // Checks whether connection knows target system ID by extracting target system if set.
920
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
1,914✔
921

922
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
1,914✔
923
        return 0;
381✔
924
    }
925

926
    // Don't look at the target system offset if it is outside the payload length.
927
    // This can happen if the fields are trimmed.
928
    if (meta->target_system_ofs >= message.len) {
1,533✔
929
        return 0;
13✔
930
    }
931

932
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,520✔
933
}
934

935
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
×
936
{
937
    // Checks whether connection knows target system ID by extracting target system if set.
938
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
×
939

940
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
×
941
        return 0;
×
942
    }
943

944
    // Don't look at the target component offset if it is outside the payload length.
945
    // This can happen if the fields are trimmed.
946
    if (meta->target_component_ofs >= message.len) {
×
947
        return 0;
×
948
    }
949

950
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
×
951
}
952

953
Sender& MavsdkImpl::sender()
×
954
{
955
    return default_server_component_impl().sender();
×
956
}
957

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