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

mavlink / MAVSDK / 5231532789

pending completion
5231532789

push

github

web-flow
Merge pull request #2079 from mavlink/pr-remove-connection

core: add way to remove a connection

48 of 48 new or added lines in 2 files covered. (100.0%)

7691 of 24905 relevant lines covered (30.88%)

21.64 hits per line

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

54.17
/src/mavsdk/core/mavsdk_impl.cpp
1
#include "mavsdk_impl.h"
2

3
#include <algorithm>
4
#include <mutex>
5

6
#include "connection.h"
7
#include "tcp_connection.h"
8
#include "udp_connection.h"
9
#include "system.h"
10
#include "system_impl.h"
11
#include "serial_connection.h"
12
#include "cli_arg.h"
13
#include "version.h"
14
#include "server_component_impl.h"
15
#include "callback_list.tpp"
16

17
namespace mavsdk {
18

19
template class CallbackList<>;
20

21
MavsdkImpl::MavsdkImpl() : timeout_handler(_time), call_every_handler(_time)
21✔
22
{
23
    LogInfo() << "MAVSDK version: " << mavsdk_version;
21✔
24

25
    if (const char* env_p = std::getenv("MAVSDK_CALLBACK_DEBUGGING")) {
21✔
26
        if (std::string(env_p) == "1") {
×
27
            LogDebug() << "Callback debugging is on.";
×
28
            _callback_debugging = true;
×
29
        }
30
    }
31

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

39
    _work_thread = new std::thread(&MavsdkImpl::work_thread, this);
21✔
40

41
    _process_user_callbacks_thread =
42✔
42
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
21✔
43
}
21✔
44

45
MavsdkImpl::~MavsdkImpl()
21✔
46
{
47
    call_every_handler.remove(_heartbeat_send_cookie);
21✔
48

49
    _should_exit = true;
21✔
50

51
    if (_process_user_callbacks_thread != nullptr) {
21✔
52
        _user_callback_queue.stop();
21✔
53
        _process_user_callbacks_thread->join();
21✔
54
        delete _process_user_callbacks_thread;
21✔
55
        _process_user_callbacks_thread = nullptr;
21✔
56
    }
57

58
    if (_work_thread != nullptr) {
21✔
59
        _work_thread->join();
21✔
60
        delete _work_thread;
21✔
61
        _work_thread = nullptr;
21✔
62
    }
63

64
    {
65
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
42✔
66
        _systems.clear();
21✔
67
    }
68

69
    {
70
        std::lock_guard<std::mutex> lock(_connections_mutex);
42✔
71
        _connections.clear();
21✔
72
    }
73
}
21✔
74

75
std::string MavsdkImpl::version()
1✔
76
{
77
    static unsigned version_counter = 0;
78

79
    ++version_counter;
1✔
80

81
    switch (version_counter) {
1✔
82
        case 10:
×
83
            return "You were wondering about the name of this library?";
×
84
        case 11:
×
85
            return "Let's look at the history:";
×
86
        case 12:
×
87
            return "DroneLink";
×
88
        case 13:
×
89
            return "DroneCore";
×
90
        case 14:
×
91
            return "DronecodeSDK";
×
92
        case 15:
×
93
            return "MAVSDK";
×
94
        case 16:
×
95
            return "And that's it...";
×
96
        case 17:
×
97
            return "At least for now ¯\\_(ツ)_/¯.";
×
98
        default:
1✔
99
            return mavsdk_version;
1✔
100
    }
101
}
102

103
std::vector<std::shared_ptr<System>> MavsdkImpl::systems() const
20✔
104
{
105
    std::vector<std::shared_ptr<System>> systems_result{};
20✔
106

107
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
40✔
108
    for (auto& system : _systems) {
31✔
109
        // We ignore the 0 entry because it's just a null system.
110
        // It's only created because the older, deprecated API needs a
111
        // reference.
112
        if (system.first == 0) {
11✔
113
            continue;
×
114
        }
115
        systems_result.push_back(system.second);
11✔
116
    }
117

118
    return systems_result;
20✔
119
}
120

121
std::optional<std::shared_ptr<System>> MavsdkImpl::first_autopilot(double timeout_s)
9✔
122
{
123
    {
124
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
9✔
125
        for (auto system : _systems) {
10✔
126
            if (system.second->is_connected() && system.second->has_autopilot()) {
1✔
127
                return system.second;
×
128
            }
129
        }
130
    }
131

132
    if (timeout_s == 0.0) {
9✔
133
        // Don't wait at all.
134
        return {};
×
135
    }
136

137
    auto prom = std::promise<std::shared_ptr<System>>();
18✔
138

139
    std::once_flag flag;
9✔
140
    auto handle = subscribe_on_new_system([this, &prom, &flag]() {
9✔
141
        const auto system = systems().at(0);
27✔
142
        if (system->is_connected() && system->has_autopilot()) {
9✔
143
            std::call_once(flag, [&prom, &system]() { prom.set_value(system); });
18✔
144
        }
145
    });
9✔
146

147
    auto fut = prom.get_future();
18✔
148

149
    if (timeout_s > 0.0) {
9✔
150
        if (fut.wait_for(std::chrono::milliseconds(int64_t(timeout_s * 1e3))) ==
9✔
151
            std::future_status::ready) {
152
            unsubscribe_on_new_system(handle);
9✔
153
            return fut.get();
9✔
154

155
        } else {
156
            unsubscribe_on_new_system(handle);
×
157
            return std::nullopt;
×
158
        }
159
    } else {
160
        fut.wait();
×
161
        unsubscribe_on_new_system(handle);
×
162
        return std::optional(fut.get());
×
163
    }
164
}
165

166
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_type(
10✔
167
    Mavsdk::ServerComponentType server_component_type, unsigned instance)
168
{
169
    switch (server_component_type) {
10✔
170
        case Mavsdk::ServerComponentType::Autopilot:
9✔
171
            if (instance == 0) {
9✔
172
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1);
9✔
173
            } else {
174
                LogErr() << "Only autopilot instance 0 is valid";
×
175
                return {};
×
176
            }
177

178
        case Mavsdk::ServerComponentType::GroundStation:
×
179
            if (instance == 0) {
×
180
                return server_component_by_id(MAV_COMP_ID_MISSIONPLANNER);
×
181
            } else {
182
                LogErr() << "Only one ground station supported at this time";
×
183
                return {};
×
184
            }
185

186
        case Mavsdk::ServerComponentType::CompanionComputer:
×
187
            if (instance == 0) {
×
188
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER);
×
189
            } else if (instance == 1) {
×
190
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER2);
×
191
            } else if (instance == 2) {
×
192
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER3);
×
193
            } else if (instance == 3) {
×
194
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER4);
×
195
            } else {
196
                LogErr() << "Only companion computer 0..3 are supported";
×
197
                return {};
×
198
            }
199

200
        case Mavsdk::ServerComponentType::Camera:
1✔
201
            if (instance == 0) {
1✔
202
                return server_component_by_id(MAV_COMP_ID_CAMERA);
1✔
203
            } else if (instance == 1) {
×
204
                return server_component_by_id(MAV_COMP_ID_CAMERA2);
×
205
            } else if (instance == 2) {
×
206
                return server_component_by_id(MAV_COMP_ID_CAMERA3);
×
207
            } else if (instance == 3) {
×
208
                return server_component_by_id(MAV_COMP_ID_CAMERA4);
×
209
            } else if (instance == 4) {
×
210
                return server_component_by_id(MAV_COMP_ID_CAMERA5);
×
211
            } else if (instance == 5) {
×
212
                return server_component_by_id(MAV_COMP_ID_CAMERA6);
×
213
            } else {
214
                LogErr() << "Only camera 0..5 are supported";
×
215
                return {};
×
216
            }
217

218
        default:
×
219
            LogErr() << "Unknown server component type";
×
220
            return {};
×
221
    }
222
}
223

224
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id(uint8_t component_id)
30✔
225
{
226
    if (component_id == 0) {
30✔
227
        LogErr() << "Server component with component ID 0 not allowed";
×
228
        return nullptr;
×
229
    }
230

231
    std::lock_guard<std::mutex> lock(_server_components_mutex);
60✔
232

233
    for (auto& it : _server_components) {
30✔
234
        if (it.first == component_id) {
10✔
235
            if (it.second != nullptr) {
10✔
236
                return it.second;
10✔
237
            } else {
238
                it.second = std::make_shared<ServerComponent>(*this, component_id);
×
239
            }
240
        }
241
    }
242

243
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
60✔
244
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
80✔
245

246
    return _server_components.back().second;
20✔
247
}
248

249
void MavsdkImpl::forward_message(mavlink_message_t& message, Connection* connection)
×
250
{
251
    // Forward_message Function implementing Mavlink routing rules.
252
    // See https://mavlink.io/en/guide/routing.html
253

254
    bool forward_heartbeats_enabled = true;
×
255
    const uint8_t target_system_id = get_target_system_id(message);
×
256
    const uint8_t target_component_id = get_target_component_id(message);
×
257

258
    // If it's a message only for us, we keep it, otherwise, we forward it.
259
    const bool targeted_only_at_us =
260
        (target_system_id == get_own_system_id() && target_component_id == get_own_component_id());
×
261

262
    // We don't forward heartbeats unless it's specifically enabled.
263
    const bool heartbeat_check_ok =
×
264
        (message.msgid != MAVLINK_MSG_ID_HEARTBEAT || forward_heartbeats_enabled);
×
265

266
    if (!targeted_only_at_us && heartbeat_check_ok) {
×
267
        std::lock_guard<std::mutex> lock(_connections_mutex);
×
268

269
        unsigned successful_emissions = 0;
×
270
        for (auto& entry : _connections) {
×
271
            // Check whether the connection is not the one from which we received the message.
272
            // And also check if the connection was set to forward messages.
273
            if (entry.connection.get() == connection ||
×
274
                !entry.connection->should_forward_messages()) {
×
275
                continue;
×
276
            }
277
            if ((*entry.connection).send_message(message)) {
×
278
                successful_emissions++;
×
279
            }
280
        }
281
        if (successful_emissions == 0) {
×
282
            LogErr() << "Message forwarding failed";
×
283
        }
284
    }
285
}
×
286

287
void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connection)
190✔
288
{
289
    if (_message_logging_on) {
190✔
290
        LogDebug() << "Processing message " << message.msgid << " from "
×
291
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
292
    }
293

294
    // This is a low level interface where incoming messages can be tampered
295
    // with or even dropped.
296
    {
297
        std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
190✔
298
        if (_intercept_incoming_messages_callback != nullptr) {
190✔
299
            bool keep = _intercept_incoming_messages_callback(message);
51✔
300
            if (!keep) {
51✔
301
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
15✔
302
                return;
15✔
303
            }
304
        }
305
    }
306

307
    /** @note: Forward message if option is enabled and multiple interfaces are connected.
308
     *  Performs message forwarding checks for every messages if message forwarding
309
     *  is enabled on at least one connection, and in case of a single forwarding connection,
310
     *  we check that it is not the one which received the current message.
311
     *
312
     * Conditions:
313
     * 1. At least 2 connections.
314
     * 2. At least 1 forwarding connection.
315
     * 3. At least 2 forwarding connections or current connection is not forwarding.
316
     */
317
    if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
175✔
318
        (mavsdk::Connection::forwarding_connections_count() > 1 ||
×
319
         !connection->should_forward_messages())) {
×
320
        if (_message_logging_on) {
×
321
            LogDebug() << "Forwarding message " << message.msgid << " from "
×
322
                       << static_cast<int>(message.sysid) << "/"
×
323
                       << static_cast<int>(message.compid);
×
324
        }
325
        forward_message(message, connection);
×
326
    }
327

328
    // Don't ever create a system with sysid 0.
329
    if (message.sysid == 0) {
175✔
330
        if (_message_logging_on) {
×
331
            LogDebug() << "Ignoring message with sysid == 0";
×
332
        }
333
        return;
×
334
    }
335

336
    // Filter out messages by QGroundControl, however, only do that if MAVSDK
337
    // is also implementing a ground station and not if it is used in another
338
    // configuration, e.g. on a companion.
339
    //
340
    // This is a workaround because PX4 started forwarding messages between
341
    // mavlink instances which leads to existing implementations (including
342
    // examples and integration tests) to connect to QGroundControl by accident
343
    // instead of PX4 because the check `has_autopilot()` is not used.
344
    if (_configuration.get_usage_type() == Mavsdk::Configuration::UsageType::GroundStation &&
175✔
345
        message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
175✔
346
        if (_message_logging_on) {
×
347
            LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
348
        }
349
        return;
×
350
    }
351

352
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
175✔
353

354
    // The only situation where we create a system with sysid 0 is when we initialize the connection
355
    // to the remote.
356
    if (_systems.size() == 1 && _systems[0].first == 0) {
175✔
357
        LogDebug() << "New: System ID: " << static_cast<int>(message.sysid)
30✔
358
                   << " Comp ID: " << static_cast<int>(message.compid);
30✔
359
        _systems[0].first = message.sysid;
10✔
360
        _systems[0].second->system_impl()->set_system_id(message.sysid);
10✔
361

362
        // Even though the fake system was already discovered, we can now
363
        // send a notification, now that it seems to really actually exist.
364
        notify_on_discover();
10✔
365
    }
366

367
    bool found_system = false;
175✔
368
    for (auto& system : _systems) {
175✔
369
        if (system.first == message.sysid) {
165✔
370
            system.second->system_impl()->add_new_component(message.compid);
165✔
371
            found_system = true;
165✔
372
            break;
165✔
373
        }
374
    }
375

376
    if (!found_system && message.compid == MAV_COMP_ID_TELEMETRY_RADIO) {
175✔
377
        if (_message_logging_on) {
×
378
            LogDebug() << "Don't create new system just for telemetry radio";
×
379
        }
380
        return;
×
381
    }
382

383
    if (!found_system) {
175✔
384
        make_system_with_component(message.sysid, message.compid);
10✔
385
    }
386

387
    if (_should_exit) {
175✔
388
        // Don't try to call at() if systems have already been destroyed
389
        // in destructor.
390
        return;
2✔
391
    }
392

393
    for (auto& system : _systems) {
173✔
394
        if (system.first == message.sysid) {
173✔
395
            // system.second->system_impl()->process_mavlink_message(message);
396
            mavlink_message_handler.process_message(message);
173✔
397
            break;
173✔
398
        }
399
    }
400
}
401

402
bool MavsdkImpl::send_message(mavlink_message_t& message)
192✔
403
{
404
    if (_message_logging_on) {
192✔
405
        LogDebug() << "Sending message " << message.msgid << " from "
×
406
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
407
    }
408

409
    // This is a low level interface where outgoing messages can be tampered
410
    // with or even dropped.
411
    if (_intercept_outgoing_messages_callback != nullptr) {
192✔
412
        const bool keep = _intercept_outgoing_messages_callback(message);
×
413
        if (!keep) {
×
414
            // We fake that everything was sent as instructed because
415
            // a potential loss would happen later, and we would not be informed
416
            // about it.
417
            LogDebug() << "Dropped outgoing message: " << int(message.msgid);
×
418
            return true;
×
419
        }
420
    }
421

422
    std::lock_guard<std::mutex> lock(_connections_mutex);
384✔
423

424
    if (_connections.empty()) {
192✔
425
        // We obviously can't send any messages without a connection added, so
426
        // we silently ignore this.
427
        return true;
1✔
428
    }
429

430
    uint8_t successful_emissions = 0;
191✔
431
    for (auto& _connection : _connections) {
382✔
432
        const uint8_t target_system_id = get_target_system_id(message);
191✔
433

434
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
191✔
435
            continue;
×
436
        }
437

438
        if ((*_connection.connection).send_message(message)) {
191✔
439
            successful_emissions++;
191✔
440
        }
441
    }
442

443
    if (successful_emissions == 0) {
191✔
444
        LogErr() << "Sending message failed";
×
445
        return false;
×
446
    }
447

448
    return true;
191✔
449
}
450

451
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
20✔
452
    const std::string& connection_url, ForwardingOption forwarding_option)
453
{
454
    CliArg cli_arg;
40✔
455
    if (!cli_arg.parse(connection_url)) {
20✔
456
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
457
    }
458

459
    switch (cli_arg.get_protocol()) {
20✔
460
        case CliArg::Protocol::Udp: {
20✔
461
            int port = cli_arg.get_port() ? cli_arg.get_port() : Mavsdk::DEFAULT_UDP_PORT;
20✔
462

463
            if (cli_arg.get_path().empty() || cli_arg.get_path() == Mavsdk::DEFAULT_UDP_BIND_IP) {
20✔
464
                std::string path = Mavsdk::DEFAULT_UDP_BIND_IP;
30✔
465
                return add_udp_connection(path, port, forwarding_option);
10✔
466
            } else {
467
                std::string path = cli_arg.get_path();
20✔
468
                return setup_udp_remote(path, port, forwarding_option);
10✔
469
            }
470
        }
471

472
        case CliArg::Protocol::Tcp: {
×
473
            std::string path = Mavsdk::DEFAULT_TCP_REMOTE_IP;
×
474
            int port = Mavsdk::DEFAULT_TCP_REMOTE_PORT;
×
475
            if (!cli_arg.get_path().empty()) {
×
476
                path = cli_arg.get_path();
×
477
            }
478
            if (cli_arg.get_port()) {
×
479
                port = cli_arg.get_port();
×
480
            }
481
            return add_tcp_connection(path, port, forwarding_option);
×
482
        }
483

484
        case CliArg::Protocol::Serial: {
×
485
            int baudrate = Mavsdk::DEFAULT_SERIAL_BAUDRATE;
×
486
            if (cli_arg.get_baudrate()) {
×
487
                baudrate = cli_arg.get_baudrate();
×
488
            }
489
            bool flow_control = cli_arg.get_flow_control();
×
490
            return add_serial_connection(
491
                cli_arg.get_path(), baudrate, flow_control, forwarding_option);
×
492
        }
493

494
        default:
×
495
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
496
    }
497
}
498

499
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_udp_connection(
10✔
500
    const std::string& local_ip, const int local_port, ForwardingOption forwarding_option)
501
{
502
    auto new_conn = std::make_shared<UdpConnection>(
10✔
503
        [this](mavlink_message_t& message, Connection* connection) {
111✔
504
            receive_message(message, connection);
111✔
505
        },
111✔
506
        local_ip,
507
        local_port,
508
        forwarding_option);
20✔
509
    if (!new_conn) {
10✔
510
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
511
    }
512
    ConnectionResult ret = new_conn->start();
10✔
513
    if (ret == ConnectionResult::Success) {
10✔
514
        return {ret, add_connection(new_conn)};
10✔
515
    } else {
516
        return {ret, Mavsdk::ConnectionHandle{}};
×
517
    }
518
}
519

520
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::setup_udp_remote(
10✔
521
    const std::string& remote_ip, int remote_port, ForwardingOption forwarding_option)
522
{
523
    auto new_conn = std::make_shared<UdpConnection>(
10✔
524
        [this](mavlink_message_t& message, Connection* connection) {
79✔
525
            receive_message(message, connection);
79✔
526
        },
79✔
527
        "0.0.0.0",
528
        0,
10✔
529
        forwarding_option);
20✔
530
    if (!new_conn) {
10✔
531
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
532
    }
533
    ConnectionResult ret = new_conn->start();
10✔
534
    if (ret == ConnectionResult::Success) {
10✔
535
        new_conn->add_remote(remote_ip, remote_port);
10✔
536
        auto handle = add_connection(new_conn);
10✔
537
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
20✔
538
        make_system_with_component(0, 0);
10✔
539
        return {ret, handle};
10✔
540
    } else {
541
        return {ret, Mavsdk::ConnectionHandle{}};
×
542
    }
543
}
544

545
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_tcp_connection(
×
546
    const std::string& remote_ip, int remote_port, ForwardingOption forwarding_option)
547
{
548
    auto new_conn = std::make_shared<TcpConnection>(
×
549
        [this](mavlink_message_t& message, Connection* connection) {
×
550
            receive_message(message, connection);
×
551
        },
×
552
        remote_ip,
553
        remote_port,
554
        forwarding_option);
×
555
    if (!new_conn) {
×
556
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
557
    }
558
    ConnectionResult ret = new_conn->start();
×
559
    if (ret == ConnectionResult::Success) {
×
560
        return {ret, add_connection(new_conn)};
×
561
    } else {
562
        return {ret, Mavsdk::ConnectionHandle{}};
×
563
    }
564
}
565

566
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
567
    const std::string& dev_path,
568
    int baudrate,
569
    bool flow_control,
570
    ForwardingOption forwarding_option)
571
{
572
    auto new_conn = std::make_shared<SerialConnection>(
×
573
        [this](mavlink_message_t& message, Connection* connection) {
×
574
            receive_message(message, connection);
×
575
        },
×
576
        dev_path,
577
        baudrate,
578
        flow_control,
579
        forwarding_option);
×
580
    if (!new_conn) {
×
581
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
582
    }
583
    ConnectionResult ret = new_conn->start();
×
584
    if (ret == ConnectionResult::Success) {
×
585
        auto handle = add_connection(new_conn);
×
586

587
        auto new_configuration = get_configuration();
×
588

589
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
590
        // to initiate the MAVLink connection by sending heartbeats.
591
        // Therefore, we override the default here and enable sending heartbeats.
592
        new_configuration.set_always_send_heartbeats(true);
×
593
        set_configuration(new_configuration);
×
594

595
        return {ret, handle};
×
596

597
    } else {
598
        return {ret, Mavsdk::ConnectionHandle{}};
×
599
    }
600
}
601

602
Mavsdk::ConnectionHandle
603
MavsdkImpl::add_connection(const std::shared_ptr<Connection>& new_connection)
20✔
604
{
605
    std::lock_guard<std::mutex> lock(_connections_mutex);
20✔
606
    auto handle = Mavsdk::ConnectionHandle{_connections_handle_id++};
20✔
607
    _connections.emplace_back(ConnectionEntry{new_connection, handle});
20✔
608

609
    return handle;
20✔
610
}
611

612
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
×
613
{
614
    std::lock_guard<std::mutex> lock(_connections_mutex);
×
615

616
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
×
617
        return (entry.handle == handle);
×
618
    }));
×
619
}
×
620

621
Mavsdk::Configuration MavsdkImpl::get_configuration() const
×
622
{
623
    return _configuration;
×
624
}
625

626
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
20✔
627
{
628
    // We just point the default to the newly created component. This means
629
    // that the previous default component will be deleted if it is not
630
    // used/referenced anywhere.
631
    _default_server_component = server_component_by_id(new_configuration.get_component_id());
20✔
632

633
    if (new_configuration.get_always_send_heartbeats() &&
30✔
634
        !_configuration.get_always_send_heartbeats()) {
10✔
635
        start_sending_heartbeats();
10✔
636
    } else if (
10✔
637
        !new_configuration.get_always_send_heartbeats() &&
20✔
638
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
20✔
639
        stop_sending_heartbeats();
×
640
    }
641

642
    _configuration = new_configuration;
20✔
643
}
20✔
644

645
uint8_t MavsdkImpl::get_own_system_id() const
252✔
646
{
647
    return _configuration.get_system_id();
252✔
648
}
649

650
uint8_t MavsdkImpl::get_own_component_id() const
83✔
651
{
652
    return _configuration.get_component_id();
83✔
653
}
654

655
// FIXME: this should be per component
656
uint8_t MavsdkImpl::get_mav_type() const
26✔
657
{
658
    switch (_configuration.get_usage_type()) {
26✔
659
        case Mavsdk::Configuration::UsageType::Autopilot:
14✔
660
            return MAV_TYPE_GENERIC;
14✔
661

662
        case Mavsdk::Configuration::UsageType::GroundStation:
11✔
663
            return MAV_TYPE_GCS;
11✔
664

665
        case Mavsdk::Configuration::UsageType::CompanionComputer:
×
666
            return MAV_TYPE_ONBOARD_CONTROLLER;
×
667

668
        case Mavsdk::Configuration::UsageType::Camera:
1✔
669
            return MAV_TYPE_CAMERA;
1✔
670

671
        case Mavsdk::Configuration::UsageType::Custom:
×
672
            return MAV_TYPE_GENERIC;
×
673

674
        default:
×
675
            LogErr() << "Unknown configuration";
×
676
            return 0;
×
677
    }
678
}
679

680
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
20✔
681
{
682
    // Needs _systems_lock
683

684
    if (_should_exit) {
20✔
685
        // When the system got destroyed in the destructor, we have to give up.
686
        return;
×
687
    }
688

689
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
20✔
690
        LogDebug() << "Initializing connection to remote system...";
10✔
691
    } else {
692
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
30✔
693
                   << " Comp ID: " << static_cast<int>(comp_id);
30✔
694
    }
695

696
    // Make a system with its first component
697
    auto new_system = std::make_shared<System>(*this);
40✔
698
    new_system->init(system_id, comp_id);
20✔
699

700
    _systems.emplace_back(system_id, new_system);
20✔
701
}
702

703
void MavsdkImpl::notify_on_discover()
28✔
704
{
705
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
56✔
706
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
38✔
707
}
28✔
708

709
void MavsdkImpl::notify_on_timeout()
×
710
{
711
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
×
712
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
713
}
×
714

715
Mavsdk::NewSystemHandle
716
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
10✔
717
{
718
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
10✔
719

720
    const auto handle = _new_system_callbacks.subscribe(callback);
10✔
721

722
    if (is_any_system_connected()) {
10✔
723
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
724
    }
725

726
    return handle;
10✔
727
}
728

729
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
10✔
730
{
731
    _new_system_callbacks.unsubscribe(handle);
10✔
732
}
10✔
733

734
bool MavsdkImpl::is_any_system_connected() const
10✔
735
{
736
    std::vector<std::shared_ptr<System>> connected_systems = systems();
20✔
737
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
10✔
738
        return system->is_connected();
1✔
739
    });
10✔
740
}
741

742
void MavsdkImpl::work_thread()
1,591✔
743
{
744
    while (!_should_exit) {
1,591✔
745
        timeout_handler.run_once();
1,568✔
746
        call_every_handler.run_once();
1,567✔
747

748
        {
749
            std::lock_guard<std::mutex> lock(_server_components_mutex);
3,140✔
750
            for (auto& it : _server_components) {
3,119✔
751
                if (it.second != nullptr) {
1,547✔
752
                    it.second->_impl->do_work();
1,547✔
753
                }
754
            }
755
        }
756

757
        std::this_thread::sleep_for(std::chrono::milliseconds(10));
1,570✔
758
    }
759
}
21✔
760

761
void MavsdkImpl::call_user_callback_located(
42✔
762
    const std::string& filename, const int linenumber, const std::function<void()>& func)
763
{
764
    auto callback_size = _user_callback_queue.size();
42✔
765
    if (callback_size == 10) {
42✔
766
        LogWarn()
×
767
            << "User callback queue too slow.\n"
×
768
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
769

770
    } else if (callback_size == 99) {
42✔
771
        LogErr()
×
772
            << "User callback queue overflown\n"
×
773
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
774

775
    } else if (callback_size == 100) {
42✔
776
        return;
×
777
    }
778

779
    // We only need to keep track of filename and linenumber if we're actually debugging this.
780
    UserCallback user_callback =
42✔
781
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
126✔
782

783
    _user_callback_queue.enqueue(user_callback);
42✔
784
}
785

786
void MavsdkImpl::process_user_callbacks_thread()
84✔
787
{
788
    while (!_should_exit) {
84✔
789
        auto callback = _user_callback_queue.dequeue();
63✔
790
        if (!callback) {
63✔
791
            continue;
21✔
792
        }
793

794
        void* cookie{nullptr};
42✔
795

796
        const double timeout_s = 1.0;
42✔
797
        timeout_handler.add(
42✔
798
            [&]() {
×
799
                if (_callback_debugging) {
×
800
                    LogWarn() << "Callback called from " << callback.value().filename << ":"
×
801
                              << callback.value().linenumber << " took more than " << timeout_s
×
802
                              << " second to run.";
×
803
                    fflush(stdout);
×
804
                    fflush(stderr);
×
805
                    abort();
×
806
                } else {
807
                    LogWarn()
×
808
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
809
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
810
                }
811
            },
×
812
            timeout_s,
813
            &cookie);
814
        callback.value().func();
42✔
815
        timeout_handler.remove(cookie);
42✔
816
    }
817
}
21✔
818

819
void MavsdkImpl::start_sending_heartbeats()
28✔
820
{
821
    // Before sending out first heartbeats we need to make sure we have a
822
    // default server component.
823
    if (_default_server_component == nullptr) {
28✔
824
        _default_server_component = server_component_by_id(_configuration.get_component_id());
×
825
    }
826

827
    if (_heartbeat_send_cookie == nullptr) {
28✔
828
        call_every_handler.add(
20✔
829
            [this]() { send_heartbeat(); }, HEARTBEAT_SEND_INTERVAL_S, &_heartbeat_send_cookie);
26✔
830
    }
831
}
28✔
832

833
void MavsdkImpl::stop_sending_heartbeats()
×
834
{
835
    if (!_configuration.get_always_send_heartbeats()) {
×
836
        call_every_handler.remove(_heartbeat_send_cookie);
×
837
        _heartbeat_send_cookie = nullptr;
×
838
    }
839
}
×
840

841
void MavsdkImpl::send_heartbeat()
26✔
842
{
843
    std::lock_guard<std::mutex> lock(_server_components_mutex);
52✔
844

845
    for (auto& it : _server_components) {
52✔
846
        if (it.second != nullptr) {
26✔
847
            it.second->_impl->send_heartbeat();
26✔
848
        }
849
    }
850
}
26✔
851

852
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
12✔
853
{
854
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
24✔
855
    _intercept_incoming_messages_callback = callback;
12✔
856
}
12✔
857

858
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
×
859
{
860
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
×
861
    _intercept_outgoing_messages_callback = callback;
×
862
}
×
863

864
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
191✔
865
{
866
    // Checks whether connection knows target system ID by extracting target system if set.
867
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
191✔
868

869
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
191✔
870
        return 0;
101✔
871
    }
872

873
    // Don't look at the target system offset if it is outside the payload length.
874
    // This can happen if the fields are trimmed.
875
    if (meta->target_system_ofs >= message.len) {
90✔
876
        return 0;
×
877
    }
878

879
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
90✔
880
}
881

882
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
×
883
{
884
    // Checks whether connection knows target system ID by extracting target system if set.
885
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
×
886

887
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
×
888
        return 0;
×
889
    }
890

891
    // Don't look at the target component offset if it is outside the payload length.
892
    // This can happen if the fields are trimmed.
893
    if (meta->target_component_ofs >= message.len) {
×
894
        return 0;
×
895
    }
896

897
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
×
898
}
899

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