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

mavlink / MAVSDK / 16233609062

12 Jul 2025 02:58AM UTC coverage: 45.799% (+0.6%) from 45.212%
16233609062

Pull #2610

github

web-flow
Merge 313266bea into 6c112e71f
Pull Request #2610: Integrate parts of libmav into MAVSDK and add MavlinkDirect plugin

473 of 727 new or added lines in 14 files covered. (65.06%)

35 existing lines in 7 files now uncovered.

15955 of 34837 relevant lines covered (45.8%)

145116.67 hits per line

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

62.57
/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) :
95✔
27
    timeout_handler(time),
95✔
28
    call_every_handler(time)
190✔
29
{
30
    LogInfo() << "MAVSDK version: " << mavsdk_version;
95✔
31

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

53
    set_configuration(configuration);
95✔
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 =
190✔
59
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
95✔
60

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

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

71
    _should_exit = true;
95✔
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) {
95✔
77
        _work_thread->join();
95✔
78
        delete _work_thread;
95✔
79
        _work_thread = nullptr;
95✔
80
    }
81

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

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

91
    _systems.clear();
95✔
92
    _connections.clear();
95✔
93
}
190✔
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
106✔
124
{
125
    std::vector<std::shared_ptr<System>> systems_result{};
106✔
126

127
    std::lock_guard lock(_mutex);
106✔
128
    for (auto& system : _systems) {
161✔
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) {
55✔
133
            continue;
×
134
        }
135
        systems_result.push_back(system.second);
55✔
136
    }
137

138
    return systems_result;
106✔
139
}
106✔
140

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

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

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

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

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

173
    if (timeout_s > 0.0) {
37✔
174
        if (fut.wait_for(std::chrono::milliseconds(int64_t(timeout_s * 1e3))) ==
37✔
175
            std::future_status::ready) {
176
            unsubscribe_on_new_system(handle);
37✔
177
            return fut.get();
37✔
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
}
37✔
189

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

194
    auto component_type = _configuration.get_component_type();
48✔
195
    switch (component_type) {
48✔
196
        case ComponentType::Autopilot:
48✔
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);
48✔
204
        default:
×
205
            LogErr() << "Unknown component type";
×
206
            return {};
×
207
    }
208
}
48✔
209

210
std::shared_ptr<ServerComponent>
211
MavsdkImpl::server_component_by_type(ComponentType server_component_type, unsigned instance)
48✔
212
{
213
    switch (server_component_type) {
48✔
214
        case ComponentType::Autopilot:
34✔
215
            if (instance == 0) {
34✔
216
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1);
34✔
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)
48✔
269
{
270
    if (component_id == 0) {
48✔
271
        LogErr() << "Server component with component ID 0 not allowed";
×
272
        return nullptr;
×
273
    }
274

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

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

280
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id_with_lock(uint8_t component_id)
189✔
281
{
282
    for (auto& it : _server_components) {
190✔
283
        if (it.first == component_id) {
94✔
284
            if (it.second != nullptr) {
93✔
285
                return it.second;
93✔
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>>(
192✔
293
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
192✔
294

295
    return _server_components.back().second;
96✔
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,121✔
340
{
341
    {
342
        std::lock_guard lock(_received_messages_mutex);
2,121✔
343
        _received_messages.emplace(ReceivedMessage{std::move(message), connection});
2,129✔
344
    }
2,131✔
345
    _received_messages_cv.notify_one();
2,130✔
346
}
2,131✔
347

348
void MavsdkImpl::receive_libmav_message(const LibmavMessage& message, Connection* connection)
1,907✔
349
{
350
    {
351
        std::lock_guard lock(_received_libmav_messages_mutex);
1,907✔
352
        _received_libmav_messages.emplace(ReceivedLibmavMessage{message, connection});
1,907✔
353
    }
1,907✔
354
    _received_libmav_messages_cv.notify_one();
1,907✔
355
}
1,907✔
356

357
void MavsdkImpl::process_messages()
21,857✔
358
{
359
    std::lock_guard lock(_received_messages_mutex);
21,857✔
360
    while (!_received_messages.empty()) {
23,879✔
361
        auto message_copied = _received_messages.front();
2,120✔
362
        process_message(message_copied.message, message_copied.connection_ptr);
2,120✔
363
        _received_messages.pop();
2,120✔
364
    }
365
}
21,475✔
366

367
void MavsdkImpl::process_libmav_messages()
21,751✔
368
{
369
    std::lock_guard lock(_received_libmav_messages_mutex);
21,751✔
370
    while (!_received_libmav_messages.empty()) {
23,465✔
371
        auto message_copied = _received_libmav_messages.front();
1,905✔
372
        process_libmav_message(message_copied.message, message_copied.connection_ptr);
1,905✔
373
        _received_libmav_messages.pop();
1,905✔
374
    }
1,905✔
375
}
21,674✔
376

377
void MavsdkImpl::process_message(mavlink_message_t& message, Connection* connection)
2,120✔
378
{
379
    // Assumes _received_messages_mutex
380

381
    if (_message_logging_on) {
2,120✔
382
        LogDebug() << "Processing message " << message.msgid << " from "
×
383
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
384
    }
385

386
    if (_should_exit) {
2,120✔
387
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
388
        return;
×
389
    }
390

391
    {
392
        std::lock_guard lock(_mutex);
2,120✔
393

394
        // This is a low level interface where incoming messages can be tampered
395
        // with or even dropped.
396
        {
397
            bool keep = true;
2,120✔
398
            {
399
                std::lock_guard<std::mutex> intercept_lock(_intercept_callbacks_mutex);
2,120✔
400
                if (_intercept_incoming_messages_callback != nullptr) {
2,120✔
401
                    keep = _intercept_incoming_messages_callback(message);
237✔
402
                }
403
            }
2,120✔
404

405
            if (!keep) {
2,120✔
406
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
32✔
407
                return;
32✔
408
            }
409
        }
410

411
        if (_should_exit) {
2,088✔
412
            // If we're meant to clean up, let's not try to acquire any more locks but bail.
413
            return;
×
414
        }
415

416
        /** @note: Forward message if option is enabled and multiple interfaces are connected.
417
         *  Performs message forwarding checks for every messages if message forwarding
418
         *  is enabled on at least one connection, and in case of a single forwarding connection,
419
         *  we check that it is not the one which received the current message.
420
         *
421
         * Conditions:
422
         * 1. At least 2 connections.
423
         * 2. At least 1 forwarding connection.
424
         * 3. At least 2 forwarding connections or current connection is not forwarding.
425
         */
426

427
        if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
2,088✔
428
            (mavsdk::Connection::forwarding_connections_count() > 1 ||
×
429
             !connection->should_forward_messages())) {
×
430
            if (_message_logging_on) {
×
431
                LogDebug() << "Forwarding message " << message.msgid << " from "
×
432
                           << static_cast<int>(message.sysid) << "/"
×
433
                           << static_cast<int>(message.compid);
×
434
            }
435
            forward_message(message, connection);
×
436
        }
437

438
        // Don't ever create a system with sysid 0.
439
        if (message.sysid == 0) {
2,088✔
440
            if (_message_logging_on) {
×
441
                LogDebug() << "Ignoring message with sysid == 0";
×
442
            }
443
            return;
×
444
        }
445

446
        // Filter out messages by QGroundControl, however, only do that if MAVSDK
447
        // is also implementing a ground station and not if it is used in another
448
        // configuration, e.g. on a companion.
449
        //
450
        // This is a workaround because PX4 started forwarding messages between
451
        // mavlink instances which leads to existing implementations (including
452
        // examples and integration tests) to connect to QGroundControl by accident
453
        // instead of PX4 because the check `has_autopilot()` is not used.
454

455
        if (_configuration.get_component_type() == ComponentType::GroundStation &&
2,088✔
456
            message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
2,088✔
457
            if (_message_logging_on) {
×
458
                LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
459
            }
460
            return;
×
461
        }
462

463
        bool found_system = false;
2,088✔
464
        for (auto& system : _systems) {
2,088✔
465
            if (system.first == message.sysid) {
1,994✔
466
                system.second->system_impl()->add_new_component(message.compid);
1,994✔
467
                found_system = true;
1,994✔
468
                break;
1,994✔
469
            }
470
        }
471

472
        if (!found_system) {
2,088✔
473
            if (_system_debugging) {
94✔
474
                LogWarn() << "Create new system/component " << (int)message.sysid << "/"
×
475
                          << (int)message.compid;
×
476
                LogWarn() << "From message " << (int)message.msgid << " with len "
×
477
                          << (int)message.len;
×
478
                std::string bytes = "";
×
479
                for (unsigned i = 0; i < 12 + message.len; ++i) {
×
480
                    bytes += std::to_string(reinterpret_cast<uint8_t*>(&message)[i]) + ' ';
×
481
                }
482
                LogWarn() << "Bytes: " << bytes;
×
483
            }
×
484
            make_system_with_component(message.sysid, message.compid);
94✔
485

486
            // We now better talk back.
487
            start_sending_heartbeats();
94✔
488
        }
489

490
        if (_should_exit) {
2,088✔
491
            // Don't try to call at() if systems have already been destroyed
492
            // in destructor.
493
            return;
×
494
        }
495
    }
2,120✔
496

497
    mavlink_message_handler.process_message(message);
2,088✔
498

499
    for (auto& system : _systems) {
2,088✔
500
        if (system.first == message.sysid) {
2,088✔
501
            system.second->system_impl()->process_mavlink_message(message);
2,088✔
502
            break;
2,088✔
503
        }
504
    }
505
}
506

507
void MavsdkImpl::process_libmav_message(const LibmavMessage& message, Connection* /* connection */)
1,905✔
508
{
509
    // Assumes _received_libmav_messages_mutex
510

511
    if (_message_logging_on) {
1,905✔
NEW
512
        LogDebug() << "MavsdkImpl::process_libmav_message: " << message.message_name << " from "
×
NEW
513
                   << static_cast<int>(message.system_id) << "/"
×
NEW
514
                   << static_cast<int>(message.component_id);
×
515
    }
516

517
    if (_message_logging_on) {
1,905✔
NEW
518
        LogDebug() << "Processing libmav message " << message.message_name << " from "
×
NEW
519
                   << static_cast<int>(message.system_id) << "/"
×
NEW
520
                   << static_cast<int>(message.component_id);
×
521
    }
522

523
    if (_should_exit) {
1,905✔
524
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
NEW
525
        return;
×
526
    }
527

528
    {
529
        std::lock_guard lock(_mutex);
1,905✔
530

531
        // Don't ever create a system with sysid 0.
532
        if (message.system_id == 0) {
1,905✔
NEW
533
            if (_message_logging_on) {
×
NEW
534
                LogDebug() << "Ignoring libmav message with sysid == 0";
×
535
            }
NEW
536
            return;
×
537
        }
538

539
        // Filter out QGroundControl messages similar to regular mavlink processing
540
        if (_configuration.get_component_type() == ComponentType::GroundStation &&
1,905✔
541
            message.system_id == 255 && message.component_id == MAV_COMP_ID_MISSIONPLANNER) {
1,905✔
NEW
542
            if (_message_logging_on) {
×
NEW
543
                LogDebug() << "Ignoring libmav messages from QGC as we are also a ground station";
×
544
            }
NEW
545
            return;
×
546
        }
547

548
        bool found_system = false;
1,905✔
549
        for (auto& system : _systems) {
1,905✔
550
            if (system.first == message.system_id) {
1,905✔
551
                system.second->system_impl()->add_new_component(message.component_id);
1,905✔
552
                found_system = true;
1,905✔
553
                break;
1,905✔
554
            }
555
        }
556

557
        if (!found_system) {
1,905✔
NEW
558
            if (_system_debugging) {
×
NEW
559
                LogWarn() << "Create new system/component from libmav " << (int)message.system_id
×
NEW
560
                          << "/" << (int)message.component_id;
×
561
            }
NEW
562
            make_system_with_component(message.system_id, message.component_id);
×
563

564
            // We now better talk back.
NEW
565
            start_sending_heartbeats();
×
566
        }
567

568
        if (_should_exit) {
1,905✔
569
            // Don't try to call at() if systems have already been destroyed
570
            // in destructor.
NEW
571
            return;
×
572
        }
573
    }
1,905✔
574

575
    // Distribute libmav message to systems for libmav-specific handling
576
    bool found_system = false;
1,905✔
577
    for (auto& system : _systems) {
3,810✔
578
        if (system.first == message.system_id) {
1,905✔
579
            if (_message_logging_on) {
1,905✔
NEW
580
                LogDebug() << "Distributing libmav message " << message.message_name
×
NEW
581
                           << " to SystemImpl for system " << system.first;
×
582
            }
583
            system.second->system_impl()->process_libmav_message(message);
1,905✔
584
            found_system = true;
1,905✔
585
            // Don't break - distribute to all matching system instances
586
        }
587
    }
588

589
    if (!found_system) {
1,905✔
NEW
590
        LogWarn() << "No system found for libmav message " << message.message_name
×
NEW
591
                  << " from system " << message.system_id;
×
592
    }
593
}
594

595
bool MavsdkImpl::send_message(mavlink_message_t& message)
2,263✔
596
{
597
    // Create a copy of the message to avoid reference issues
598
    mavlink_message_t message_copy = message;
2,263✔
599

600
    {
601
        std::lock_guard lock(_messages_to_send_mutex);
2,263✔
602
        _messages_to_send.push(std::move(message_copy));
2,263✔
603
    }
2,263✔
604

605
    // For heartbeat messages, we want to process them immediately to speed up system discovery
606
    if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
2,263✔
607
        // Trigger message processing in the work thread
608
        // This is a hint to process messages sooner, but doesn't block
609
        std::this_thread::yield();
259✔
610
    }
611

612
    return true;
2,263✔
613
}
614

615
void MavsdkImpl::deliver_messages()
24,119✔
616
{
617
    // Process messages one at a time to avoid holding the mutex while delivering
618
    while (true) {
619
        mavlink_message_t message;
24,119✔
620
        {
621
            std::lock_guard lock(_messages_to_send_mutex);
23,901✔
622
            if (_messages_to_send.empty()) {
23,785✔
623
                break;
21,738✔
624
            }
625
            message = _messages_to_send.front();
2,263✔
626
            _messages_to_send.pop();
2,262✔
627
        }
24,000✔
628
        deliver_message(message);
2,262✔
629
    }
2,263✔
630
}
21,423✔
631

632
void MavsdkImpl::deliver_message(mavlink_message_t& message)
2,263✔
633
{
634
    if (_message_logging_on) {
2,263✔
635
        LogDebug() << "Sending message " << message.msgid << " from "
×
636
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid)
×
637
                   << " to " << static_cast<int>(get_target_system_id(message)) << "/"
×
638
                   << static_cast<int>(get_target_component_id(message));
×
639
    }
640

641
    // This is a low level interface where outgoing messages can be tampered
642
    // with or even dropped.
643
    bool keep = true;
2,263✔
644
    {
645
        std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
2,263✔
646
        if (_intercept_outgoing_messages_callback != nullptr) {
2,263✔
647
            keep = _intercept_outgoing_messages_callback(message);
220✔
648
        }
649
    }
2,262✔
650

651
    if (!keep) {
2,263✔
652
        // We fake that everything was sent as instructed because
653
        // a potential loss would happen later, and we would not be informed
654
        // about it.
655
        LogDebug() << "Dropped outgoing message: " << int(message.msgid);
88✔
656
        return;
88✔
657
    }
658

659
    std::lock_guard lock(_mutex);
2,175✔
660

661
    if (_connections.empty()) {
2,174✔
662
        // We obviously can't send any messages without a connection added, so
663
        // we silently ignore this.
664
        return;
47✔
665
    }
666

667
    uint8_t successful_emissions = 0;
2,126✔
668
    for (auto& _connection : _connections) {
4,254✔
669
        const uint8_t target_system_id = get_target_system_id(message);
2,126✔
670

671
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
2,128✔
672
            continue;
×
673
        }
674
        const auto result = (*_connection.connection).send_message(message);
2,128✔
675
        if (result.first) {
2,128✔
676
            successful_emissions++;
2,128✔
677
        } else {
678
            _connections_errors_subscriptions.queue(
×
679
                Mavsdk::ConnectionError{result.second, _connection.handle},
×
680
                [this](const auto& func) { call_user_callback(func); });
×
681
        }
682
    }
2,128✔
683

684
    if (successful_emissions == 0) {
2,126✔
685
        LogErr() << "Sending message failed";
×
686
    }
687
}
2,173✔
688

689
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
94✔
690
    const std::string& connection_url, ForwardingOption forwarding_option)
691
{
692
    CliArg cli_arg;
94✔
693
    if (!cli_arg.parse(connection_url)) {
94✔
694
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
695
    }
696

697
    return std::visit(
94✔
698
        overloaded{
188✔
699
            [](std::monostate) {
×
700
                // Should not happen anyway.
701
                return std::pair<ConnectionResult, Mavsdk::ConnectionHandle>{
×
702
                    ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle()};
×
703
            },
704
            [this, forwarding_option](const CliArg::Udp& udp) {
92✔
705
                return add_udp_connection(udp, forwarding_option);
92✔
706
            },
707
            [this, forwarding_option](const CliArg::Tcp& tcp) {
2✔
708
                return add_tcp_connection(tcp, forwarding_option);
2✔
709
            },
710
            [this, forwarding_option](const CliArg::Serial& serial) {
×
711
                return add_serial_connection(
×
712
                    serial.path, serial.baudrate, serial.flow_control_enabled, forwarding_option);
×
713
            }},
714
        cli_arg.protocol);
94✔
715
}
94✔
716

717
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
718
MavsdkImpl::add_udp_connection(const CliArg::Udp& udp, ForwardingOption forwarding_option)
92✔
719
{
720
    auto new_conn = std::make_unique<UdpConnection>(
92✔
721
        [this](mavlink_message_t& message, Connection* connection) {
2,109✔
722
            receive_message(message, connection);
2,109✔
723
        },
2,112✔
724
        [this](const LibmavMessage& message, Connection* connection) {
1,907✔
725
            receive_libmav_message(message, connection);
1,907✔
726
        },
1,907✔
727
        udp.mode == CliArg::Udp::Mode::In ? udp.host : "0.0.0.0",
230✔
728
        udp.mode == CliArg::Udp::Mode::In ? udp.port : 0,
184✔
729
        forwarding_option);
276✔
730

731
    if (!new_conn) {
92✔
732
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
733
    }
734

735
    ConnectionResult ret = new_conn->start();
92✔
736

737
    if (ret != ConnectionResult::Success) {
92✔
738
        return {ret, Mavsdk::ConnectionHandle{}};
×
739
    }
740

741
    if (udp.mode == CliArg::Udp::Mode::Out) {
92✔
742
        // We need to add the IP rather than a hostname, otherwise we end up with two remotes:
743
        // one for the IP, and one for a hostname.
744
        auto remote_ip = resolve_hostname_to_ip(udp.host);
46✔
745

746
        if (!remote_ip) {
46✔
747
            return {ConnectionResult::DestinationIpUnknown, Mavsdk::ConnectionHandle{}};
×
748
        }
749

750
        new_conn->add_remote_to_keep(remote_ip.value(), udp.port);
46✔
751
        std::lock_guard lock(_mutex);
46✔
752

753
        // With a UDP remote, we need to initiate the connection by sending heartbeats.
754
        auto new_configuration = get_configuration();
46✔
755
        new_configuration.set_always_send_heartbeats(true);
46✔
756
        set_configuration(new_configuration);
46✔
757
    }
46✔
758

759
    auto handle = add_connection(std::move(new_conn));
92✔
760

761
    return {ConnectionResult::Success, handle};
92✔
762
}
92✔
763

764
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
765
MavsdkImpl::add_tcp_connection(const CliArg::Tcp& tcp, ForwardingOption forwarding_option)
2✔
766
{
767
    if (tcp.mode == CliArg::Tcp::Mode::Out) {
2✔
768
        auto new_conn = std::make_unique<TcpClientConnection>(
1✔
769
            [this](mavlink_message_t& message, Connection* connection) {
7✔
770
                receive_message(message, connection);
7✔
771
            },
7✔
NEW
772
            [this](const LibmavMessage& message, Connection* connection) {
×
NEW
773
                receive_libmav_message(message, connection);
×
NEW
774
            },
×
775
            tcp.host,
1✔
776
            tcp.port,
1✔
777
            forwarding_option);
1✔
778
        if (!new_conn) {
1✔
779
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
780
        }
781
        ConnectionResult ret = new_conn->start();
1✔
782
        if (ret == ConnectionResult::Success) {
1✔
783
            return {ret, add_connection(std::move(new_conn))};
1✔
784
        } else {
785
            return {ret, Mavsdk::ConnectionHandle{}};
×
786
        }
787
    } else {
1✔
788
        auto new_conn = std::make_unique<TcpServerConnection>(
1✔
789
            [this](mavlink_message_t& message, Connection* connection) {
12✔
790
                receive_message(message, connection);
12✔
791
            },
12✔
NEW
792
            [this](const LibmavMessage& message, Connection* connection) {
×
NEW
793
                receive_libmav_message(message, connection);
×
NEW
794
            },
×
795
            tcp.host,
1✔
796
            tcp.port,
1✔
797
            forwarding_option);
1✔
798
        if (!new_conn) {
1✔
799
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
800
        }
801
        ConnectionResult ret = new_conn->start();
1✔
802
        if (ret == ConnectionResult::Success) {
1✔
803
            return {ret, add_connection(std::move(new_conn))};
1✔
804
        } else {
805
            return {ret, Mavsdk::ConnectionHandle{}};
×
806
        }
807
    }
1✔
808
}
809

810
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
811
    const std::string& dev_path,
812
    int baudrate,
813
    bool flow_control,
814
    ForwardingOption forwarding_option)
815
{
816
    auto new_conn = std::make_unique<SerialConnection>(
×
817
        [this](mavlink_message_t& message, Connection* connection) {
×
818
            receive_message(message, connection);
×
819
        },
×
NEW
820
        [this](const LibmavMessage& message, Connection* connection) {
×
NEW
821
            receive_libmav_message(message, connection);
×
NEW
822
        },
×
823
        dev_path,
824
        baudrate,
825
        flow_control,
826
        forwarding_option);
×
827
    if (!new_conn) {
×
828
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
829
    }
830
    ConnectionResult ret = new_conn->start();
×
831
    if (ret == ConnectionResult::Success) {
×
832
        auto handle = add_connection(std::move(new_conn));
×
833

834
        auto new_configuration = get_configuration();
×
835

836
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
837
        // to initiate the MAVLink connection by sending heartbeats.
838
        // Therefore, we override the default here and enable sending heartbeats.
839
        new_configuration.set_always_send_heartbeats(true);
×
840
        set_configuration(new_configuration);
×
841

842
        return {ret, handle};
×
843

844
    } else {
845
        return {ret, Mavsdk::ConnectionHandle{}};
×
846
    }
847
}
×
848

849
Mavsdk::ConnectionHandle MavsdkImpl::add_connection(std::unique_ptr<Connection>&& new_connection)
94✔
850
{
851
    std::lock_guard lock(_mutex);
94✔
852
    auto handle = _connections_handle_factory.create();
94✔
853
    _connections.emplace_back(ConnectionEntry{std::move(new_connection), handle});
94✔
854

855
    return handle;
188✔
856
}
94✔
857

858
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
×
859
{
860
    std::lock_guard lock(_mutex);
×
861

862
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
×
863
        return (entry.handle == handle);
×
864
    }));
865
}
×
866

867
Mavsdk::Configuration MavsdkImpl::get_configuration() const
46✔
868
{
869
    std::lock_guard configuration_lock(_mutex);
46✔
870
    return _configuration;
92✔
871
}
46✔
872

873
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
141✔
874
{
875
    std::lock_guard server_components_lock(_server_components_mutex);
141✔
876
    // We just point the default to the newly created component. This means
877
    // that the previous default component will be deleted if it is not
878
    // used/referenced anywhere.
879
    _default_server_component =
141✔
880
        server_component_by_id_with_lock(new_configuration.get_component_id());
141✔
881

882
    if (new_configuration.get_always_send_heartbeats() &&
234✔
883
        !_configuration.get_always_send_heartbeats()) {
93✔
884
        start_sending_heartbeats();
47✔
885
    } else if (
94✔
886
        !new_configuration.get_always_send_heartbeats() &&
142✔
887
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
142✔
888
        stop_sending_heartbeats();
×
889
    }
890

891
    _configuration = new_configuration;
141✔
892
    // We cache these values as atomic to avoid having to lock any mutex for them.
893
    _our_system_id = new_configuration.get_system_id();
141✔
894
    _our_component_id = new_configuration.get_component_id();
141✔
895
}
141✔
896

897
uint8_t MavsdkImpl::get_own_system_id() const
5,209✔
898
{
899
    return _our_system_id;
5,209✔
900
}
901

902
uint8_t MavsdkImpl::get_own_component_id() const
1,386✔
903
{
904
    return _our_component_id;
1,386✔
905
}
906

907
uint8_t MavsdkImpl::channel() const
×
908
{
909
    // TODO
910
    return 0;
×
911
}
912

913
Autopilot MavsdkImpl::autopilot() const
×
914
{
915
    // TODO
916
    return Autopilot::Px4;
×
917
}
918

919
// FIXME: this should be per component
920
uint8_t MavsdkImpl::get_mav_type() const
259✔
921
{
922
    return _configuration.get_mav_type();
259✔
923
}
924

925
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
94✔
926
{
927
    // Needs _systems_lock
928

929
    if (_should_exit) {
94✔
930
        // When the system got destroyed in the destructor, we have to give up.
931
        return;
×
932
    }
933

934
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
94✔
935
        LogDebug() << "Initializing connection to remote system...";
×
936
    } else {
937
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
282✔
938
                   << " Comp ID: " << static_cast<int>(comp_id);
282✔
939
    }
940

941
    // Make a system with its first component
942
    auto new_system = std::make_shared<System>(*this);
94✔
943
    new_system->init(system_id, comp_id);
94✔
944

945
    _systems.emplace_back(system_id, new_system);
94✔
946
}
94✔
947

948
void MavsdkImpl::notify_on_discover()
94✔
949
{
950
    // Queue the callbacks without holding the mutex to avoid deadlocks
951
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
141✔
952
}
94✔
953

954
void MavsdkImpl::notify_on_timeout()
×
955
{
956
    // Queue the callbacks without holding the mutex to avoid deadlocks
957
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
958
}
×
959

960
Mavsdk::NewSystemHandle
961
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
47✔
962
{
963
    std::lock_guard lock(_mutex);
47✔
964

965
    const auto handle = _new_system_callbacks.subscribe(callback);
47✔
966

967
    if (is_any_system_connected()) {
47✔
968
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
969
    }
970

971
    return handle;
94✔
972
}
47✔
973

974
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
46✔
975
{
976
    _new_system_callbacks.unsubscribe(handle);
46✔
977
}
46✔
978

979
bool MavsdkImpl::is_any_system_connected() const
47✔
980
{
981
    std::vector<std::shared_ptr<System>> connected_systems = systems();
47✔
982
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
47✔
983
        return system->is_connected();
×
984
    });
47✔
985
}
47✔
986

987
void MavsdkImpl::work_thread()
95✔
988
{
989
    while (!_should_exit) {
21,843✔
990
        // Process incoming messages
991
        process_messages();
21,649✔
992

993
        // Process incoming libmav messages
994
        process_libmav_messages();
21,849✔
995

996
        // Run timers
997
        timeout_handler.run_once();
21,577✔
998
        call_every_handler.run_once();
21,780✔
999

1000
        // Do component work
1001
        {
1002
            std::lock_guard lock(_server_components_mutex);
21,869✔
1003
            for (auto& it : _server_components) {
43,665✔
1004
                if (it.second != nullptr) {
21,898✔
1005
                    it.second->_impl->do_work();
21,896✔
1006
                }
1007
            }
1008
        }
21,400✔
1009

1010
        // Deliver outgoing messages
1011
        deliver_messages();
21,496✔
1012

1013
        // If no messages to send, check if there are messages to receive
1014
        std::unique_lock lock_received(_received_messages_mutex);
21,839✔
1015
        if (_received_messages.empty()) {
21,716✔
1016
            // No messages to process, wait for a signal or timeout
1017
            _received_messages_cv.wait_for(lock_received, std::chrono::milliseconds(10), [this]() {
21,306✔
1018
                return !_received_messages.empty() || _should_exit;
42,917✔
1019
            });
1020
        }
1021
    }
21,764✔
1022
}
125✔
1023

1024
void MavsdkImpl::call_user_callback_located(
1,062✔
1025
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1026
{
1027
    // Don't enqueue callbacks if we're shutting down
1028
    if (_should_exit) {
1,062✔
1029
        return;
×
1030
    }
1031

1032
    auto callback_size = _user_callback_queue.size();
1,062✔
1033
    if (callback_size == 10) {
1,062✔
1034
        LogWarn()
4✔
1035
            << "User callback queue too slow.\n"
2✔
1036
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
2✔
1037

1038
    } else if (callback_size == 99) {
1,060✔
1039
        LogErr()
×
1040
            << "User callback queue overflown\n"
×
1041
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1042

1043
    } else if (callback_size == 100) {
1,060✔
1044
        return;
×
1045
    }
1046

1047
    // We only need to keep track of filename and linenumber if we're actually debugging this.
1048
    UserCallback user_callback =
1,062✔
1049
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
2,124✔
1050

1051
    _user_callback_queue.push_back(std::make_shared<UserCallback>(user_callback));
1,062✔
1052
}
1,062✔
1053

1054
void MavsdkImpl::process_user_callbacks_thread()
95✔
1055
{
1056
    while (!_should_exit) {
1,252✔
1057
        std::shared_ptr<UserCallback> callback;
1,157✔
1058
        {
1059
            LockedQueue<UserCallback>::Guard guard(_user_callback_queue);
1,157✔
1060
            callback = guard.wait_and_pop_front();
1,157✔
1061
        }
1,157✔
1062

1063
        if (!callback) {
1,157✔
1064
            continue;
95✔
1065
        }
1066

1067
        // Check if we're in the process of shutting down before executing the callback
1068
        if (_should_exit) {
1,062✔
1069
            continue;
×
1070
        }
1071

1072
        const double timeout_s = 1.0;
1,062✔
1073
        auto cookie = timeout_handler.add(
1,062✔
1074
            [&]() {
×
1075
                if (_callback_debugging) {
×
1076
                    LogWarn() << "Callback called from " << callback->filename << ":"
×
1077
                              << callback->linenumber << " took more than " << timeout_s
×
1078
                              << " second to run.";
×
1079
                    fflush(stdout);
×
1080
                    fflush(stderr);
×
1081
                    abort();
×
1082
                } else {
1083
                    LogWarn()
×
1084
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
1085
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
1086
                }
1087
            },
×
1088
            timeout_s);
1,062✔
1089
        callback->func();
1,062✔
1090
        timeout_handler.remove(cookie);
1,062✔
1091
    }
1,157✔
1092
}
95✔
1093

1094
void MavsdkImpl::start_sending_heartbeats()
235✔
1095
{
1096
    // Check if we're in the process of shutting down
1097
    if (_should_exit) {
235✔
1098
        return;
×
1099
    }
1100

1101
    // Before sending out first heartbeats we need to make sure we have a
1102
    // default server component.
1103
    default_server_component_impl();
235✔
1104

1105
    {
1106
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
235✔
1107
        call_every_handler.remove(_heartbeat_send_cookie);
235✔
1108
        _heartbeat_send_cookie =
470✔
1109
            call_every_handler.add([this]() { send_heartbeats(); }, HEARTBEAT_SEND_INTERVAL_S);
492✔
1110
    }
235✔
1111
}
1112

1113
void MavsdkImpl::stop_sending_heartbeats()
×
1114
{
1115
    if (!_configuration.get_always_send_heartbeats()) {
×
1116
        std::lock_guard<std::mutex> lock(_heartbeat_mutex);
×
1117
        call_every_handler.remove(_heartbeat_send_cookie);
×
1118
    }
×
1119
}
×
1120

1121
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
1,105✔
1122
{
1123
    std::lock_guard lock(_server_components_mutex);
1,105✔
1124
    return default_server_component_with_lock();
1,105✔
1125
}
1,105✔
1126

1127
ServerComponentImpl& MavsdkImpl::default_server_component_with_lock()
1,105✔
1128
{
1129
    if (_default_server_component == nullptr) {
1,105✔
1130
        _default_server_component = server_component_by_id_with_lock(_our_component_id);
×
1131
    }
1132
    return *_default_server_component->_impl;
1,105✔
1133
}
1134

1135
void MavsdkImpl::send_heartbeats()
256✔
1136
{
1137
    std::lock_guard lock(_server_components_mutex);
256✔
1138

1139
    for (auto& it : _server_components) {
514✔
1140
        if (it.second != nullptr) {
259✔
1141
            it.second->_impl->send_heartbeat();
259✔
1142
        }
1143
    }
1144
}
257✔
1145

1146
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
22✔
1147
{
1148
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
22✔
1149
    _intercept_incoming_messages_callback = callback;
22✔
1150
}
22✔
1151

1152
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
1153
{
1154
    std::lock_guard<std::mutex> lock(_intercept_callbacks_mutex);
14✔
1155
    _intercept_outgoing_messages_callback = callback;
14✔
1156
}
14✔
1157

1158
Mavsdk::ConnectionErrorHandle
1159
MavsdkImpl::subscribe_connection_errors(Mavsdk::ConnectionErrorCallback callback)
×
1160
{
1161
    std::lock_guard lock(_mutex);
×
1162

1163
    const auto handle = _connections_errors_subscriptions.subscribe(callback);
×
1164

1165
    return handle;
×
1166
}
×
1167

1168
void MavsdkImpl::unsubscribe_connection_errors(Mavsdk::ConnectionErrorHandle handle)
×
1169
{
1170
    std::lock_guard lock(_mutex);
×
1171
    _connections_errors_subscriptions.unsubscribe(handle);
×
1172
}
×
1173

1174
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
2,128✔
1175
{
1176
    // Checks whether connection knows target system ID by extracting target system if set.
1177
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
2,128✔
1178

1179
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
2,127✔
1180
        return 0;
397✔
1181
    }
1182

1183
    // Don't look at the target system offset if it is outside the payload length.
1184
    // This can happen if the fields are trimmed.
1185
    if (meta->target_system_ofs >= message.len) {
1,730✔
1186
        return 0;
5✔
1187
    }
1188

1189
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,725✔
1190
}
1191

1192
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
×
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);
×
1196

1197
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
×
1198
        return 0;
×
1199
    }
1200

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

1207
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
×
1208
}
1209

1210
Sender& MavsdkImpl::sender()
×
1211
{
1212
    std::lock_guard lock(_server_components_mutex);
×
1213
    return default_server_component_with_lock().sender();
×
1214
}
×
1215

1216
std::vector<Connection*> MavsdkImpl::get_connections() const
4✔
1217
{
1218
    std::vector<Connection*> connections;
4✔
1219
    for (const auto& connection_entry : _connections) {
8✔
1220
        connections.push_back(connection_entry.connection.get());
4✔
1221
    }
1222
    return connections;
4✔
1223
}
1224

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