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

mavlink / MAVSDK / 4899817366

pending completion
4899817366

Pull #1772

github

GitHub
Merge c0bb90862 into e4e9c71dd
Pull Request #1772: Refactor MAVLinkParameters into client and server classes

2192 of 2192 new or added lines in 34 files covered. (100.0%)

7708 of 24812 relevant lines covered (31.07%)

19.96 hits per line

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

55.11
/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) {
35✔
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) {
15✔
113
            continue;
×
114
        }
115
        systems_result.push_back(system.second);
15✔
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) {
13✔
126
            if (system.second->is_connected() && system.second->has_autopilot()) {
4✔
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& _connection : _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 (_connection.get() == connection || !(*_connection).should_forward_messages()) {
×
274
                continue;
×
275
            }
276
            if ((*_connection).send_message(message)) {
×
277
                successful_emissions++;
×
278
            }
279
        }
280
        if (successful_emissions == 0) {
×
281
            LogErr() << "Message forwarding failed";
×
282
        }
283
    }
284
}
×
285

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

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

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

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

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

351
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
190✔
352

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

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

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

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

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

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

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

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

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

421
    std::lock_guard<std::mutex> lock(_connections_mutex);
412✔
422

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

429
    uint8_t successful_emissions = 0;
206✔
430
    for (auto& _connection : _connections) {
412✔
431
        const uint8_t target_system_id = get_target_system_id(message);
206✔
432

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

437
        if ((*_connection).send_message(message)) {
206✔
438
            successful_emissions++;
206✔
439
        }
440
    }
441

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

447
    return true;
206✔
448
}
449

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

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

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

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

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

493
        default:
×
494
            return ConnectionResult::ConnectionError;
×
495
    }
496
}
497

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

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

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

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

583
    auto new_configuration = get_configuration();
×
584

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

591
    return ret;
×
592
}
593

594
void MavsdkImpl::add_connection(const std::shared_ptr<Connection>& new_connection)
20✔
595
{
596
    std::lock_guard<std::mutex> lock(_connections_mutex);
40✔
597
    _connections.push_back(new_connection);
20✔
598
}
20✔
599

600
Mavsdk::Configuration MavsdkImpl::get_configuration() const
×
601
{
602
    return _configuration;
×
603
}
604

605
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
20✔
606
{
607
    // We just point the default to the newly created component. This means
608
    // that the previous default component will be deleted if it is not
609
    // used/referenced anywhere.
610
    _default_server_component = server_component_by_id(new_configuration.get_component_id());
20✔
611

612
    if (new_configuration.get_always_send_heartbeats() &&
30✔
613
        !_configuration.get_always_send_heartbeats()) {
10✔
614
        start_sending_heartbeats();
10✔
615
    } else if (
10✔
616
        !new_configuration.get_always_send_heartbeats() &&
20✔
617
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
20✔
618
        stop_sending_heartbeats();
×
619
    }
620

621
    _configuration = new_configuration;
20✔
622
}
20✔
623

624
uint8_t MavsdkImpl::get_own_system_id() const
261✔
625
{
626
    return _configuration.get_system_id();
261✔
627
}
628

629
uint8_t MavsdkImpl::get_own_component_id() const
94✔
630
{
631
    return _configuration.get_component_id();
94✔
632
}
633

634
// FIXME: this should be per component
635
uint8_t MavsdkImpl::get_mav_type() const
22✔
636
{
637
    switch (_configuration.get_usage_type()) {
22✔
638
        case Mavsdk::Configuration::UsageType::Autopilot:
10✔
639
            return MAV_TYPE_GENERIC;
10✔
640

641
        case Mavsdk::Configuration::UsageType::GroundStation:
11✔
642
            return MAV_TYPE_GCS;
11✔
643

644
        case Mavsdk::Configuration::UsageType::CompanionComputer:
×
645
            return MAV_TYPE_ONBOARD_CONTROLLER;
×
646

647
        case Mavsdk::Configuration::UsageType::Camera:
1✔
648
            return MAV_TYPE_CAMERA;
1✔
649

650
        case Mavsdk::Configuration::UsageType::Custom:
×
651
            return MAV_TYPE_GENERIC;
×
652

653
        default:
×
654
            LogErr() << "Unknown configuration";
×
655
            return 0;
×
656
    }
657
}
658

659
void MavsdkImpl::make_system_with_component(
20✔
660
    uint8_t system_id, uint8_t comp_id, bool always_connected)
661
{
662
    // Needs _systems_lock
663

664
    if (_should_exit) {
20✔
665
        // When the system got destroyed in the destructor, we have to give up.
666
        return;
×
667
    }
668

669
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
20✔
670
        LogDebug() << "Initializing connection to remote system...";
10✔
671
    } else {
672
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
30✔
673
                   << " Comp ID: " << static_cast<int>(comp_id);
30✔
674
    }
675

676
    // Make a system with its first component
677
    auto new_system = std::make_shared<System>(*this);
40✔
678
    new_system->init(system_id, comp_id, always_connected);
20✔
679

680
    _systems.emplace_back(system_id, new_system);
20✔
681
}
682

683
void MavsdkImpl::notify_on_discover()
20✔
684
{
685
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
40✔
686
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
30✔
687
}
20✔
688

689
void MavsdkImpl::notify_on_timeout()
×
690
{
691
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
×
692
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
693
}
×
694

695
Mavsdk::NewSystemHandle
696
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
10✔
697
{
698
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
20✔
699

700
    if (callback != nullptr && is_any_system_connected()) {
10✔
701
        call_user_callback([temp_callback = callback]() { temp_callback(); });
×
702
    }
703

704
    return _new_system_callbacks.subscribe(callback);
10✔
705
}
706

707
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
10✔
708
{
709
    _new_system_callbacks.unsubscribe(handle);
10✔
710
}
10✔
711

712
bool MavsdkImpl::is_any_system_connected() const
10✔
713
{
714
    std::vector<std::shared_ptr<System>> connected_systems = systems();
20✔
715
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
10✔
716
        return system->is_connected();
5✔
717
    });
10✔
718
}
719

720
void MavsdkImpl::work_thread()
699✔
721
{
722
    while (!_should_exit) {
699✔
723
        timeout_handler.run_once();
677✔
724
        call_every_handler.run_once();
678✔
725

726
        {
727
            std::lock_guard<std::mutex> lock(_server_components_mutex);
1,356✔
728
            for (auto& it : _server_components) {
1,335✔
729
                if (it.second != nullptr) {
657✔
730
                    it.second->_impl->do_work();
657✔
731
                }
732
            }
733
        }
734

735
        std::this_thread::sleep_for(std::chrono::milliseconds(10));
678✔
736
    }
737
}
21✔
738

739
void MavsdkImpl::call_user_callback_located(
44✔
740
    const std::string& filename, const int linenumber, const std::function<void()>& func)
741
{
742
    auto callback_size = _user_callback_queue.size();
44✔
743
    if (callback_size == 10) {
44✔
744
        LogWarn()
×
745
            << "User callback queue too slow.\n"
×
746
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
747

748
    } else if (callback_size == 99) {
44✔
749
        LogErr()
×
750
            << "User callback queue overflown\n"
×
751
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
752

753
    } else if (callback_size == 100) {
44✔
754
        return;
×
755
    }
756

757
    // We only need to keep track of filename and linenumber if we're actually debugging this.
758
    UserCallback user_callback =
44✔
759
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
132✔
760

761
    _user_callback_queue.enqueue(user_callback);
44✔
762
}
763

764
void MavsdkImpl::process_user_callbacks_thread()
86✔
765
{
766
    while (!_should_exit) {
86✔
767
        auto callback = _user_callback_queue.dequeue();
65✔
768
        if (!callback) {
65✔
769
            continue;
21✔
770
        }
771

772
        void* cookie{nullptr};
44✔
773

774
        const double timeout_s = 1.0;
44✔
775
        timeout_handler.add(
44✔
776
            [&]() {
×
777
                if (_callback_debugging) {
×
778
                    LogWarn() << "Callback called from " << callback.value().filename << ":"
×
779
                              << callback.value().linenumber << " took more than " << timeout_s
×
780
                              << " second to run.";
×
781
                    fflush(stdout);
×
782
                    fflush(stderr);
×
783
                    abort();
×
784
                } else {
785
                    LogWarn()
×
786
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
787
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
788
                }
789
            },
×
790
            timeout_s,
791
            &cookie);
792
        callback.value().func();
44✔
793
        timeout_handler.remove(cookie);
44✔
794
    }
795
}
21✔
796

797
void MavsdkImpl::start_sending_heartbeats()
30✔
798
{
799
    // Before sending out first heartbeats we need to make sure we have a
800
    // default server component.
801
    if (_default_server_component == nullptr) {
30✔
802
        _default_server_component = server_component_by_id(_configuration.get_component_id());
×
803
    }
804

805
    if (_heartbeat_send_cookie == nullptr) {
30✔
806
        call_every_handler.add(
20✔
807
            [this]() { send_heartbeat(); }, HEARTBEAT_SEND_INTERVAL_S, &_heartbeat_send_cookie);
22✔
808
    }
809
}
30✔
810

811
void MavsdkImpl::stop_sending_heartbeats()
×
812
{
813
    if (!_configuration.get_always_send_heartbeats()) {
×
814
        call_every_handler.remove(_heartbeat_send_cookie);
×
815
        _heartbeat_send_cookie = nullptr;
×
816
    }
817
}
×
818

819
void MavsdkImpl::send_heartbeat()
22✔
820
{
821
    std::lock_guard<std::mutex> lock(_server_components_mutex);
44✔
822

823
    for (auto& it : _server_components) {
44✔
824
        if (it.second != nullptr) {
22✔
825
            it.second->_impl->send_heartbeat();
22✔
826
        }
827
    }
828
}
22✔
829

830
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
12✔
831
{
832
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
24✔
833
    _intercept_incoming_messages_callback = callback;
12✔
834
}
12✔
835

836
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
×
837
{
838
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
×
839
    _intercept_outgoing_messages_callback = callback;
×
840
}
×
841

842
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
206✔
843
{
844
    // Checks whether connection knows target system ID by extracting target system if set.
845
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
206✔
846

847
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
206✔
848
        return 0;
105✔
849
    }
850

851
    // Don't look at the target system offset if it is outside the payload length.
852
    // This can happen if the fields are trimmed.
853
    if (meta->target_system_ofs >= message.len) {
101✔
854
        return 0;
10✔
855
    }
856

857
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
91✔
858
}
859

860
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
×
861
{
862
    // Checks whether connection knows target system ID by extracting target system if set.
863
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
×
864

865
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
×
866
        return 0;
×
867
    }
868

869
    // Don't look at the target component offset if it is outside the payload length.
870
    // This can happen if the fields are trimmed.
871
    if (meta->target_component_ofs >= message.len) {
×
872
        return 0;
×
873
    }
874

875
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
×
876
}
877

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

© 2025 Coveralls, Inc