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

mavlink / MAVSDK / 4119138814

pending completion
4119138814

push

github

GitHub
Merge pull request #1982 from mavlink/pr-fix-includes

7418 of 24193 relevant lines covered (30.66%)

21.6 hits per line

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

52.6
/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 "unused.h"
15
#include "server_component_impl.h"
16
#include "callback_list.tpp"
17

18
namespace mavsdk {
19

20
template class CallbackList<>;
21

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

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

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

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

42
    _process_user_callbacks_thread =
30✔
43
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
15✔
44
}
15✔
45

46
MavsdkImpl::~MavsdkImpl()
15✔
47
{
48
    call_every_handler.remove(_heartbeat_send_cookie);
15✔
49

50
    _should_exit = true;
15✔
51

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

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

65
    {
66
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
30✔
67
        _systems.clear();
15✔
68
    }
69

70
    {
71
        std::lock_guard<std::mutex> lock(_connections_mutex);
30✔
72
        _connections.clear();
15✔
73
    }
74
}
15✔
75

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

80
    ++version_counter;
1✔
81

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

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

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

119
    return systems_result;
14✔
120
}
121

122
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_type(
7✔
123
    Mavsdk::ServerComponentType server_component_type, unsigned instance)
124
{
125
    switch (server_component_type) {
7✔
126
        case Mavsdk::ServerComponentType::Autopilot:
6✔
127
            if (instance == 0) {
6✔
128
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1);
6✔
129
            } else {
130
                LogErr() << "Only autopilot instance 0 is valid";
×
131
                return {};
×
132
            }
133

134
        case Mavsdk::ServerComponentType::GroundStation:
×
135
            if (instance == 0) {
×
136
                return server_component_by_id(MAV_COMP_ID_MISSIONPLANNER);
×
137
            } else {
138
                LogErr() << "Only one ground station supported at this time";
×
139
                return {};
×
140
            }
141

142
        case Mavsdk::ServerComponentType::CompanionComputer:
×
143
            if (instance == 0) {
×
144
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER);
×
145
            } else if (instance == 1) {
×
146
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER2);
×
147
            } else if (instance == 2) {
×
148
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER3);
×
149
            } else if (instance == 3) {
×
150
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER4);
×
151
            } else {
152
                LogErr() << "Only companion computer 0..3 are supported";
×
153
                return {};
×
154
            }
155

156
        case Mavsdk::ServerComponentType::Camera:
1✔
157
            if (instance == 0) {
1✔
158
                return server_component_by_id(MAV_COMP_ID_CAMERA);
1✔
159
            } else if (instance == 1) {
×
160
                return server_component_by_id(MAV_COMP_ID_CAMERA2);
×
161
            } else if (instance == 2) {
×
162
                return server_component_by_id(MAV_COMP_ID_CAMERA3);
×
163
            } else if (instance == 3) {
×
164
                return server_component_by_id(MAV_COMP_ID_CAMERA4);
×
165
            } else if (instance == 4) {
×
166
                return server_component_by_id(MAV_COMP_ID_CAMERA5);
×
167
            } else if (instance == 5) {
×
168
                return server_component_by_id(MAV_COMP_ID_CAMERA6);
×
169
            } else {
170
                LogErr() << "Only camera 0..5 are supported";
×
171
                return {};
×
172
            }
173

174
        default:
×
175
            LogErr() << "Unknown server component type";
×
176
            return {};
×
177
    }
178
}
179

180
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id(uint8_t component_id)
21✔
181
{
182
    if (component_id == 0) {
21✔
183
        LogErr() << "Server component with component ID 0 not allowed";
×
184
        return nullptr;
×
185
    }
186

187
    std::lock_guard<std::mutex> lock(_server_components_mutex);
42✔
188

189
    for (auto& it : _server_components) {
21✔
190
        if (it.first == component_id) {
7✔
191
            if (it.second != nullptr) {
7✔
192
                return it.second;
7✔
193
            } else {
194
                it.second = std::make_shared<ServerComponent>(*this, component_id);
×
195
            }
196
        }
197
    }
198

199
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
42✔
200
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
56✔
201

202
    return _server_components.back().second;
14✔
203
}
204

205
void MavsdkImpl::forward_message(mavlink_message_t& message, Connection* connection)
×
206
{
207
    // Forward_message Function implementing Mavlink routing rules.
208
    // See https://mavlink.io/en/guide/routing.html
209

210
    bool forward_heartbeats_enabled = true;
×
211
    const uint8_t target_system_id = get_target_system_id(message);
×
212
    const uint8_t target_component_id = get_target_component_id(message);
×
213

214
    // If it's a message only for us, we keep it, otherwise, we forward it.
215
    const bool targeted_only_at_us =
216
        (target_system_id == get_own_system_id() && target_component_id == get_own_component_id());
×
217

218
    // We don't forward heartbeats unless it's specifically enabled.
219
    const bool heartbeat_check_ok =
×
220
        (message.msgid != MAVLINK_MSG_ID_HEARTBEAT || forward_heartbeats_enabled);
×
221

222
    if (!targeted_only_at_us && heartbeat_check_ok) {
×
223
        std::lock_guard<std::mutex> lock(_connections_mutex);
×
224

225
        unsigned successful_emissions = 0;
×
226
        for (auto& _connection : _connections) {
×
227
            // Check whether the connection is not the one from which we received the message.
228
            // And also check if the connection was set to forward messages.
229
            if (_connection.get() == connection || !(*_connection).should_forward_messages()) {
×
230
                continue;
×
231
            }
232
            if ((*_connection).send_message(message)) {
×
233
                successful_emissions++;
×
234
            }
235
        }
236
        if (successful_emissions == 0) {
×
237
            LogErr() << "Message forwarding failed";
×
238
        }
239
    }
240
}
×
241

242
void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connection)
308✔
243
{
244
    if (_message_logging_on) {
308✔
245
        LogDebug() << "Processing message " << message.msgid << " from "
×
246
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
247
    }
248

249
    // This is a low level interface where incoming messages can be tampered
250
    // with or even dropped.
251
    if (_intercept_incoming_messages_callback != nullptr) {
308✔
252
        bool keep = _intercept_incoming_messages_callback(message);
×
253
        if (!keep) {
×
254
            LogDebug() << "Dropped incoming message: " << int(message.msgid);
×
255
            return;
×
256
        }
257
    }
258

259
    /** @note: Forward message if option is enabled and multiple interfaces are connected.
260
     *  Performs message forwarding checks for every messages if message forwarding
261
     *  is enabled on at least one connection, and in case of a single forwarding connection,
262
     *  we check that it is not the one which received the current message.
263
     *
264
     * Conditions:
265
     * 1. At least 2 connections.
266
     * 2. At least 1 forwarding connection.
267
     * 3. At least 2 forwarding connections or current connection is not forwarding.
268
     */
269
    if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
308✔
270
        (mavsdk::Connection::forwarding_connections_count() > 1 ||
×
271
         !connection->should_forward_messages())) {
×
272
        if (_message_logging_on) {
×
273
            LogDebug() << "Forwarding message " << message.msgid << " from "
×
274
                       << static_cast<int>(message.sysid) << "/"
×
275
                       << static_cast<int>(message.compid);
×
276
        }
277
        forward_message(message, connection);
×
278
    }
279

280
    // Don't ever create a system with sysid 0.
281
    if (message.sysid == 0) {
308✔
282
        if (_message_logging_on) {
×
283
            LogDebug() << "Ignoring message with sysid == 0";
×
284
        }
285
        return;
×
286
    }
287

288
    // Filter out messages by QGroundControl, however, only do that if MAVSDK
289
    // is also implementing a ground station and not if it is used in another
290
    // configuration, e.g. on a companion.
291
    //
292
    // This is a workaround because PX4 started forwarding messages between
293
    // mavlink instances which leads to existing implementations (including
294
    // examples and integration tests) to connect to QGroundControl by accident
295
    // instead of PX4 because the check `has_autopilot()` is not used.
296
    if (_configuration.get_usage_type() == Mavsdk::Configuration::UsageType::GroundStation &&
308✔
297
        message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
308✔
298
        if (_message_logging_on) {
×
299
            LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
300
        }
301
        return;
×
302
    }
303

304
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
308✔
305

306
    // The only situation where we create a system with sysid 0 is when we initialize the connection
307
    // to the remote.
308
    if (_systems.size() == 1 && _systems[0].first == 0) {
308✔
309
        LogDebug() << "New: System ID: " << static_cast<int>(message.sysid)
21✔
310
                   << " Comp ID: " << static_cast<int>(message.compid);
21✔
311
        _systems[0].first = message.sysid;
7✔
312
        _systems[0].second->system_impl()->set_system_id(message.sysid);
7✔
313

314
        // Even though the fake system was already discovered, we can now
315
        // send a notification, now that it seems to really actually exist.
316
        notify_on_discover();
7✔
317
    }
318

319
    bool found_system = false;
308✔
320
    for (auto& system : _systems) {
308✔
321
        if (system.first == message.sysid) {
301✔
322
            system.second->system_impl()->add_new_component(message.compid);
301✔
323
            found_system = true;
301✔
324
            break;
301✔
325
        }
326
    }
327

328
    if (!found_system && message.compid == MAV_COMP_ID_TELEMETRY_RADIO) {
308✔
329
        if (_message_logging_on) {
×
330
            LogDebug() << "Don't create new system just for telemetry radio";
×
331
        }
332
        return;
×
333
    }
334

335
    if (!found_system) {
308✔
336
        make_system_with_component(message.sysid, message.compid);
7✔
337
    }
338

339
    if (_should_exit) {
308✔
340
        // Don't try to call at() if systems have already been destroyed
341
        // in destructor.
342
        return;
1✔
343
    }
344

345
    for (auto& system : _systems) {
307✔
346
        if (system.first == message.sysid) {
307✔
347
            // system.second->system_impl()->process_mavlink_message(message);
348
            mavlink_message_handler.process_message(message);
307✔
349
            break;
307✔
350
        }
351
    }
352
}
353

354
bool MavsdkImpl::send_message(mavlink_message_t& message)
308✔
355
{
356
    if (_message_logging_on) {
308✔
357
        LogDebug() << "Sending message " << message.msgid << " from "
×
358
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
359
    }
360

361
    // This is a low level interface where outgoing messages can be tampered
362
    // with or even dropped.
363
    if (_intercept_outgoing_messages_callback != nullptr) {
308✔
364
        const bool keep = _intercept_outgoing_messages_callback(message);
×
365
        if (!keep) {
×
366
            // We fake that everything was sent as instructed because
367
            // a potential loss would happen later, and we would not be informed
368
            // about it.
369
            LogDebug() << "Dropped outgoing message: " << int(message.msgid);
×
370
            return true;
×
371
        }
372
    }
373

374
    std::lock_guard<std::mutex> lock(_connections_mutex);
616✔
375

376
    if (_connections.empty()) {
308✔
377
        // We obviously can't send any messages without a connection added, so
378
        // we silently ignore this.
379
        return true;
×
380
    }
381

382
    uint8_t successful_emissions = 0;
308✔
383
    for (auto& _connection : _connections) {
616✔
384
        const uint8_t target_system_id = get_target_system_id(message);
308✔
385

386
        if (target_system_id != 0 && !(*_connection).has_system_id(target_system_id)) {
308✔
387
            continue;
×
388
        }
389

390
        if ((*_connection).send_message(message)) {
308✔
391
            successful_emissions++;
308✔
392
        }
393
    }
394

395
    if (successful_emissions == 0) {
308✔
396
        LogErr() << "Sending message failed";
×
397
        return false;
×
398
    }
399

400
    return true;
308✔
401
}
402

403
ConnectionResult MavsdkImpl::add_any_connection(
14✔
404
    const std::string& connection_url, ForwardingOption forwarding_option)
405
{
406
    CliArg cli_arg;
28✔
407
    if (!cli_arg.parse(connection_url)) {
14✔
408
        return ConnectionResult::ConnectionUrlInvalid;
×
409
    }
410

411
    switch (cli_arg.get_protocol()) {
14✔
412
        case CliArg::Protocol::Udp: {
14✔
413
            int port = cli_arg.get_port() ? cli_arg.get_port() : Mavsdk::DEFAULT_UDP_PORT;
14✔
414

415
            if (cli_arg.get_path().empty() || cli_arg.get_path() == Mavsdk::DEFAULT_UDP_BIND_IP) {
14✔
416
                std::string path = Mavsdk::DEFAULT_UDP_BIND_IP;
21✔
417
                return add_udp_connection(path, port, forwarding_option);
7✔
418
            } else {
419
                std::string path = cli_arg.get_path();
14✔
420
                return setup_udp_remote(path, port, forwarding_option);
7✔
421
            }
422
        }
423

424
        case CliArg::Protocol::Tcp: {
×
425
            std::string path = Mavsdk::DEFAULT_TCP_REMOTE_IP;
×
426
            int port = Mavsdk::DEFAULT_TCP_REMOTE_PORT;
×
427
            if (!cli_arg.get_path().empty()) {
×
428
                path = cli_arg.get_path();
×
429
            }
430
            if (cli_arg.get_port()) {
×
431
                port = cli_arg.get_port();
×
432
            }
433
            return add_tcp_connection(path, port, forwarding_option);
×
434
        }
435

436
        case CliArg::Protocol::Serial: {
×
437
            int baudrate = Mavsdk::DEFAULT_SERIAL_BAUDRATE;
×
438
            if (cli_arg.get_baudrate()) {
×
439
                baudrate = cli_arg.get_baudrate();
×
440
            }
441
            bool flow_control = cli_arg.get_flow_control();
×
442
            return add_serial_connection(
×
443
                cli_arg.get_path(), baudrate, flow_control, forwarding_option);
×
444
        }
445

446
        default:
×
447
            return ConnectionResult::ConnectionError;
×
448
    }
449
}
450

451
ConnectionResult MavsdkImpl::add_udp_connection(
7✔
452
    const std::string& local_ip, const int local_port, ForwardingOption forwarding_option)
453
{
454
    auto new_conn = std::make_shared<UdpConnection>(
7✔
455
        [this](mavlink_message_t& message, Connection* connection) {
260✔
456
            receive_message(message, connection);
260✔
457
        },
260✔
458
        local_ip,
459
        local_port,
460
        forwarding_option);
14✔
461
    if (!new_conn) {
7✔
462
        return ConnectionResult::ConnectionError;
×
463
    }
464
    ConnectionResult ret = new_conn->start();
7✔
465
    if (ret == ConnectionResult::Success) {
7✔
466
        add_connection(new_conn);
7✔
467
    }
468
    return ret;
7✔
469
}
470

471
ConnectionResult MavsdkImpl::setup_udp_remote(
7✔
472
    const std::string& remote_ip, int remote_port, ForwardingOption forwarding_option)
473
{
474
    auto new_conn = std::make_shared<UdpConnection>(
7✔
475
        [this](mavlink_message_t& message, Connection* connection) {
48✔
476
            receive_message(message, connection);
48✔
477
        },
48✔
478
        "0.0.0.0",
479
        0,
7✔
480
        forwarding_option);
14✔
481
    if (!new_conn) {
7✔
482
        return ConnectionResult::ConnectionError;
×
483
    }
484
    ConnectionResult ret = new_conn->start();
7✔
485
    if (ret == ConnectionResult::Success) {
7✔
486
        new_conn->add_remote(remote_ip, remote_port);
7✔
487
        add_connection(new_conn);
7✔
488
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
14✔
489
        make_system_with_component(0, 0, true);
7✔
490
    }
491
    return ret;
7✔
492
}
493

494
ConnectionResult MavsdkImpl::add_tcp_connection(
×
495
    const std::string& remote_ip, int remote_port, ForwardingOption forwarding_option)
496
{
497
    auto new_conn = std::make_shared<TcpConnection>(
×
498
        [this](mavlink_message_t& message, Connection* connection) {
×
499
            receive_message(message, connection);
×
500
        },
×
501
        remote_ip,
502
        remote_port,
503
        forwarding_option);
×
504
    if (!new_conn) {
×
505
        return ConnectionResult::ConnectionError;
×
506
    }
507
    ConnectionResult ret = new_conn->start();
×
508
    if (ret == ConnectionResult::Success) {
×
509
        add_connection(new_conn);
×
510
    }
511
    return ret;
×
512
}
513

514
ConnectionResult MavsdkImpl::add_serial_connection(
×
515
    const std::string& dev_path,
516
    int baudrate,
517
    bool flow_control,
518
    ForwardingOption forwarding_option)
519
{
520
    auto new_conn = std::make_shared<SerialConnection>(
×
521
        [this](mavlink_message_t& message, Connection* connection) {
×
522
            receive_message(message, connection);
×
523
        },
×
524
        dev_path,
525
        baudrate,
526
        flow_control,
527
        forwarding_option);
×
528
    if (!new_conn) {
×
529
        return ConnectionResult::ConnectionError;
×
530
    }
531
    ConnectionResult ret = new_conn->start();
×
532
    if (ret == ConnectionResult::Success) {
×
533
        add_connection(new_conn);
×
534
    }
535

536
    auto new_configuration = get_configuration();
×
537

538
    // PX4 starting with v1.13 does not send heartbeats by default, so we need
539
    // to initiate the MAVLink connection by sending heartbeats.
540
    // Therefore, we override the default here and enable sending heartbeats.
541
    new_configuration.set_always_send_heartbeats(true);
×
542
    set_configuration(new_configuration);
×
543

544
    return ret;
×
545
}
546

547
void MavsdkImpl::add_connection(const std::shared_ptr<Connection>& new_connection)
14✔
548
{
549
    std::lock_guard<std::mutex> lock(_connections_mutex);
28✔
550
    _connections.push_back(new_connection);
14✔
551
}
14✔
552

553
Mavsdk::Configuration MavsdkImpl::get_configuration() const
×
554
{
555
    return _configuration;
×
556
}
557

558
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
14✔
559
{
560
    // We just point the default to the newly created component. This means
561
    // that the previous default component will be deleted if it is not
562
    // used/referenced anywhere.
563
    _default_server_component = server_component_by_id(new_configuration.get_component_id());
14✔
564

565
    if (new_configuration.get_always_send_heartbeats() &&
21✔
566
        !_configuration.get_always_send_heartbeats()) {
7✔
567
        start_sending_heartbeats();
7✔
568
    } else if (
7✔
569
        !new_configuration.get_always_send_heartbeats() &&
14✔
570
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
14✔
571
        stop_sending_heartbeats();
×
572
    }
573

574
    _configuration = new_configuration;
14✔
575
}
14✔
576

577
uint8_t MavsdkImpl::get_own_system_id() const
321✔
578
{
579
    return _configuration.get_system_id();
321✔
580
}
581

582
uint8_t MavsdkImpl::get_own_component_id() const
58✔
583
{
584
    return _configuration.get_component_id();
58✔
585
}
586

587
// FIXME: this should be per component
588
uint8_t MavsdkImpl::get_mav_type() const
20✔
589
{
590
    switch (_configuration.get_usage_type()) {
20✔
591
        case Mavsdk::Configuration::UsageType::Autopilot:
9✔
592
            return MAV_TYPE_GENERIC;
9✔
593

594
        case Mavsdk::Configuration::UsageType::GroundStation:
10✔
595
            return MAV_TYPE_GCS;
10✔
596

597
        case Mavsdk::Configuration::UsageType::CompanionComputer:
×
598
            return MAV_TYPE_ONBOARD_CONTROLLER;
×
599

600
        case Mavsdk::Configuration::UsageType::Camera:
1✔
601
            return MAV_TYPE_CAMERA;
1✔
602

603
        case Mavsdk::Configuration::UsageType::Custom:
×
604
            return MAV_TYPE_GENERIC;
×
605

606
        default:
×
607
            LogErr() << "Unknown configuration";
×
608
            return 0;
×
609
    }
610
}
611

612
void MavsdkImpl::make_system_with_component(
14✔
613
    uint8_t system_id, uint8_t comp_id, bool always_connected)
614
{
615
    // Needs _systems_lock
616

617
    if (_should_exit) {
14✔
618
        // When the system got destroyed in the destructor, we have to give up.
619
        return;
×
620
    }
621

622
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
14✔
623
        LogDebug() << "Initializing connection to remote system...";
7✔
624
    } else {
625
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
21✔
626
                   << " Comp ID: " << static_cast<int>(comp_id);
21✔
627
    }
628

629
    // Make a system with its first component
630
    auto new_system = std::make_shared<System>(*this);
28✔
631
    new_system->init(system_id, comp_id, always_connected);
14✔
632

633
    _systems.emplace_back(system_id, new_system);
14✔
634
}
635

636
void MavsdkImpl::notify_on_discover()
14✔
637
{
638
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
28✔
639
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
21✔
640
}
14✔
641

642
void MavsdkImpl::notify_on_timeout()
×
643
{
644
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
×
645
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
646
}
×
647

648
Mavsdk::NewSystemHandle
649
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
7✔
650
{
651
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
14✔
652

653
    if (callback != nullptr && is_any_system_connected()) {
7✔
654
        call_user_callback([temp_callback = callback]() { temp_callback(); });
×
655
    }
656

657
    return _new_system_callbacks.subscribe(callback);
7✔
658
}
659

660
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
7✔
661
{
662
    _new_system_callbacks.unsubscribe(handle);
7✔
663
}
7✔
664

665
bool MavsdkImpl::is_any_system_connected() const
7✔
666
{
667
    std::vector<std::shared_ptr<System>> connected_systems = systems();
14✔
668
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
7✔
669
        return system->is_connected();
6✔
670
    });
7✔
671
}
672

673
void MavsdkImpl::work_thread()
808✔
674
{
675
    while (!_should_exit) {
808✔
676
        timeout_handler.run_once();
793✔
677
        call_every_handler.run_once();
793✔
678

679
        {
680
            std::lock_guard<std::mutex> lock(_server_components_mutex);
1,586✔
681
            for (auto& it : _server_components) {
1,571✔
682
                if (it.second != nullptr) {
778✔
683
                    it.second->_impl->do_work();
778✔
684
                }
685
            }
686
        }
687

688
        std::this_thread::sleep_for(std::chrono::milliseconds(10));
793✔
689
    }
690
}
15✔
691

692
void MavsdkImpl::call_user_callback_located(
38✔
693
    const std::string& filename, const int linenumber, const std::function<void()>& func)
694
{
695
    auto callback_size = _user_callback_queue.size();
38✔
696
    if (callback_size == 10) {
38✔
697
        LogWarn()
×
698
            << "User callback queue too slow.\n"
×
699
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
700

701
    } else if (callback_size == 99) {
38✔
702
        LogErr()
×
703
            << "User callback queue overflown\n"
×
704
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
705

706
    } else if (callback_size == 100) {
38✔
707
        return;
×
708
    }
709

710
    // We only need to keep track of filename and linenumber if we're actually debugging this.
711
    UserCallback user_callback =
38✔
712
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
114✔
713

714
    _user_callback_queue.enqueue(user_callback);
38✔
715
}
716

717
void MavsdkImpl::process_user_callbacks_thread()
68✔
718
{
719
    while (!_should_exit) {
68✔
720
        auto callback = _user_callback_queue.dequeue();
53✔
721
        if (!callback) {
53✔
722
            continue;
15✔
723
        }
724

725
        void* cookie{nullptr};
38✔
726

727
        const double timeout_s = 1.0;
38✔
728
        timeout_handler.add(
38✔
729
            [&]() {
×
730
                if (_callback_debugging) {
×
731
                    LogWarn() << "Callback called from " << callback.value().filename << ":"
×
732
                              << callback.value().linenumber << " took more than " << timeout_s
×
733
                              << " second to run.";
×
734
                    fflush(stdout);
×
735
                    fflush(stderr);
×
736
                    abort();
×
737
                } else {
738
                    LogWarn()
×
739
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
740
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
741
                }
742
            },
×
743
            timeout_s,
744
            &cookie);
745
        callback.value().func();
38✔
746
        timeout_handler.remove(cookie);
38✔
747
    }
748
}
15✔
749

750
void MavsdkImpl::start_sending_heartbeats()
21✔
751
{
752
    // Before sending out first heartbeats we need to make sure we have a
753
    // default server component.
754
    if (_default_server_component == nullptr) {
21✔
755
        _default_server_component = server_component_by_id(_configuration.get_component_id());
×
756
    }
757

758
    if (_heartbeat_send_cookie == nullptr) {
21✔
759
        call_every_handler.add(
14✔
760
            [this]() { send_heartbeat(); }, HEARTBEAT_SEND_INTERVAL_S, &_heartbeat_send_cookie);
20✔
761
    }
762
}
21✔
763

764
void MavsdkImpl::stop_sending_heartbeats()
×
765
{
766
    if (!_configuration.get_always_send_heartbeats()) {
×
767
        call_every_handler.remove(_heartbeat_send_cookie);
×
768
        _heartbeat_send_cookie = nullptr;
×
769
    }
770
}
×
771

772
void MavsdkImpl::send_heartbeat()
20✔
773
{
774
    std::lock_guard<std::mutex> lock(_server_components_mutex);
40✔
775

776
    for (auto& it : _server_components) {
40✔
777
        if (it.second != nullptr) {
20✔
778
            it.second->_impl->send_heartbeat();
20✔
779
        }
780
    }
781
}
20✔
782

783
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
×
784
{
785
    _intercept_incoming_messages_callback = callback;
×
786
}
×
787

788
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
×
789
{
790
    _intercept_outgoing_messages_callback = callback;
×
791
}
×
792

793
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
308✔
794
{
795
    // Checks whether connection knows target system ID by extracting target system if set.
796
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
308✔
797

798
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
308✔
799
        return 0;
243✔
800
    }
801

802
    // Don't look at the target system offset if it is outside the payload length.
803
    // This can happen if the fields are trimmed.
804
    if (meta->target_system_ofs >= message.len) {
65✔
805
        return 0;
7✔
806
    }
807

808
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
58✔
809
}
810

811
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
×
812
{
813
    // Checks whether connection knows target system ID by extracting target system if set.
814
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
×
815

816
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
×
817
        return 0;
×
818
    }
819

820
    // Don't look at the target component offset if it is outside the payload length.
821
    // This can happen if the fields are trimmed.
822
    if (meta->target_component_ofs >= message.len) {
×
823
        return 0;
×
824
    }
825

826
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
×
827
}
828

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