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

mavlink / MAVSDK / 8729832348

17 Apr 2024 11:10PM UTC coverage: 35.431% (-0.02%) from 35.452%
8729832348

push

github

web-flow
Merge pull request #2286 from mavlink/pr-fixups

gimbal/info: fixups

0 of 17 new or added lines in 2 files covered. (0.0%)

3 existing lines in 1 file now uncovered.

10106 of 28523 relevant lines covered (35.43%)

118.91 hits per line

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

56.02
/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 "mavlink_channels.h"
16
#include "callback_list.tpp"
17

18
namespace mavsdk {
19

20
template class CallbackList<>;
21

22
MavsdkImpl::MavsdkImpl(const Mavsdk::Configuration& configuration) :
69✔
23
    timeout_handler(time),
69✔
24
    call_every_handler(time)
69✔
25
{
26
    LogInfo() << "MAVSDK version: " << mavsdk_version;
69✔
27

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

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

42
    set_configuration(configuration);
69✔
43

44
    _work_thread = new std::thread(&MavsdkImpl::work_thread, this);
69✔
45

46
    _process_user_callbacks_thread =
138✔
47
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
69✔
48
}
69✔
49

50
MavsdkImpl::~MavsdkImpl()
69✔
51
{
52
    call_every_handler.remove(_heartbeat_send_cookie);
69✔
53

54
    _should_exit = true;
69✔
55

56
    if (_process_user_callbacks_thread != nullptr) {
69✔
57
        _user_callback_queue.stop();
69✔
58
        _process_user_callbacks_thread->join();
69✔
59
        delete _process_user_callbacks_thread;
69✔
60
        _process_user_callbacks_thread = nullptr;
69✔
61
    }
62

63
    if (_work_thread != nullptr) {
69✔
64
        _work_thread->join();
69✔
65
        delete _work_thread;
69✔
66
        _work_thread = nullptr;
69✔
67
    }
68

69
    {
70
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
138✔
71
        _systems.clear();
69✔
72
    }
73

74
    {
75
        std::lock_guard<std::mutex> lock(_connections_mutex);
138✔
76
        _connections.clear();
69✔
77
    }
78
}
69✔
79

80
std::string MavsdkImpl::version()
1✔
81
{
82
    static unsigned version_counter = 0;
83

84
    ++version_counter;
1✔
85

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

108
std::vector<std::shared_ptr<System>> MavsdkImpl::systems() const
68✔
109
{
110
    std::vector<std::shared_ptr<System>> systems_result{};
68✔
111

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

123
    return systems_result;
68✔
124
}
125

126
std::optional<std::shared_ptr<System>> MavsdkImpl::first_autopilot(double timeout_s)
33✔
127
{
128
    {
129
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
33✔
130
        for (auto system : _systems) {
33✔
131
            if (system.second->is_connected() && system.second->has_autopilot()) {
×
132
                return system.second;
×
133
            }
134
        }
135
    }
136

137
    if (timeout_s == 0.0) {
33✔
138
        // Don't wait at all.
139
        return {};
×
140
    }
141

142
    auto prom = std::promise<std::shared_ptr<System>>();
66✔
143

144
    std::once_flag flag;
33✔
145
    auto handle = subscribe_on_new_system([this, &prom, &flag]() {
33✔
146
        const auto system = systems().at(0);
99✔
147
        if (system->is_connected() && system->has_autopilot()) {
33✔
148
            std::call_once(flag, [&prom, &system]() { prom.set_value(system); });
66✔
149
        }
150
    });
33✔
151

152
    auto fut = prom.get_future();
66✔
153

154
    if (timeout_s > 0.0) {
33✔
155
        if (fut.wait_for(std::chrono::milliseconds(int64_t(timeout_s * 1e3))) ==
33✔
156
            std::future_status::ready) {
157
            unsubscribe_on_new_system(handle);
33✔
158
            return fut.get();
33✔
159

160
        } else {
161
            unsubscribe_on_new_system(handle);
×
162
            return std::nullopt;
×
163
        }
164
    } else {
165
        fut.wait();
×
166
        unsubscribe_on_new_system(handle);
×
167
        return std::optional(fut.get());
×
168
    }
169
}
170

171
std::shared_ptr<ServerComponent> MavsdkImpl::server_component(unsigned instance)
34✔
172
{
173
    auto component_type = _configuration.get_component_type();
34✔
174
    switch (component_type) {
34✔
175
        case Mavsdk::ComponentType::Autopilot:
34✔
176
        case Mavsdk::ComponentType::GroundStation:
177
        case Mavsdk::ComponentType::CompanionComputer:
178
        case Mavsdk::ComponentType::Camera:
179
        case Mavsdk::ComponentType::Custom:
180
            return server_component_by_type(component_type, instance);
34✔
181
        default:
×
182
            LogErr() << "Unknown component type";
×
183
            return {};
×
184
    }
185
}
186

187
std::shared_ptr<ServerComponent>
188
MavsdkImpl::server_component_by_type(Mavsdk::ComponentType server_component_type, unsigned instance)
34✔
189
{
190
    switch (server_component_type) {
34✔
191
        case Mavsdk::ComponentType::Autopilot:
33✔
192
            if (instance == 0) {
33✔
193
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1);
33✔
194
            } else {
195
                LogErr() << "Only autopilot instance 0 is valid";
×
196
                return {};
×
197
            }
198

199
        case Mavsdk::ComponentType::GroundStation:
×
200
            if (instance == 0) {
×
201
                return server_component_by_id(MAV_COMP_ID_MISSIONPLANNER);
×
202
            } else {
203
                LogErr() << "Only one ground station supported at this time";
×
204
                return {};
×
205
            }
206

207
        case Mavsdk::ComponentType::CompanionComputer:
×
208
            if (instance == 0) {
×
209
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER);
×
210
            } else if (instance == 1) {
×
211
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER2);
×
212
            } else if (instance == 2) {
×
213
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER3);
×
214
            } else if (instance == 3) {
×
215
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER4);
×
216
            } else {
217
                LogErr() << "Only companion computer 0..3 are supported";
×
218
                return {};
×
219
            }
220

221
        case Mavsdk::ComponentType::Camera:
1✔
222
            if (instance == 0) {
1✔
223
                return server_component_by_id(MAV_COMP_ID_CAMERA);
1✔
224
            } else if (instance == 1) {
×
225
                return server_component_by_id(MAV_COMP_ID_CAMERA2);
×
226
            } else if (instance == 2) {
×
227
                return server_component_by_id(MAV_COMP_ID_CAMERA3);
×
228
            } else if (instance == 3) {
×
229
                return server_component_by_id(MAV_COMP_ID_CAMERA4);
×
230
            } else if (instance == 4) {
×
231
                return server_component_by_id(MAV_COMP_ID_CAMERA5);
×
232
            } else if (instance == 5) {
×
233
                return server_component_by_id(MAV_COMP_ID_CAMERA6);
×
234
            } else {
235
                LogErr() << "Only camera 0..5 are supported";
×
236
                return {};
×
237
            }
238

239
        default:
×
240
            LogErr() << "Unknown server component type";
×
241
            return {};
×
242
    }
243
}
244

245
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id(uint8_t component_id)
137✔
246
{
247
    if (component_id == 0) {
137✔
248
        LogErr() << "Server component with component ID 0 not allowed";
×
249
        return nullptr;
×
250
    }
251

252
    std::lock_guard<std::mutex> lock(_server_components_mutex);
274✔
253

254
    for (auto& it : _server_components) {
137✔
255
        if (it.first == component_id) {
68✔
256
            if (it.second != nullptr) {
68✔
257
                return it.second;
68✔
258
            } else {
259
                it.second = std::make_shared<ServerComponent>(*this, component_id);
×
260
            }
261
        }
262
    }
263

264
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
207✔
265
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
276✔
266

267
    return _server_components.back().second;
69✔
268
}
269

270
void MavsdkImpl::forward_message(mavlink_message_t& message, Connection* connection)
×
271
{
272
    // Forward_message Function implementing Mavlink routing rules.
273
    // See https://mavlink.io/en/guide/routing.html
274

275
    bool forward_heartbeats_enabled = true;
×
276
    const uint8_t target_system_id = get_target_system_id(message);
×
277
    const uint8_t target_component_id = get_target_component_id(message);
×
278

279
    // If it's a message only for us, we keep it, otherwise, we forward it.
280
    const bool targeted_only_at_us =
281
        (target_system_id == get_own_system_id() && target_component_id == get_own_component_id());
×
282

283
    // We don't forward heartbeats unless it's specifically enabled.
284
    const bool heartbeat_check_ok =
×
285
        (message.msgid != MAVLINK_MSG_ID_HEARTBEAT || forward_heartbeats_enabled);
×
286

287
    if (!targeted_only_at_us && heartbeat_check_ok) {
×
288
        std::lock_guard<std::mutex> lock(_connections_mutex);
×
289

290
        unsigned successful_emissions = 0;
×
291
        for (auto& entry : _connections) {
×
292
            // Check whether the connection is not the one from which we received the message.
293
            // And also check if the connection was set to forward messages.
294
            if (entry.connection.get() == connection ||
×
295
                !entry.connection->should_forward_messages()) {
×
296
                continue;
×
297
            }
298
            if ((*entry.connection).send_message(message)) {
×
299
                successful_emissions++;
×
300
            }
301
        }
302
        if (successful_emissions == 0) {
×
303
            LogErr() << "Message forwarding failed";
×
304
        }
305
    }
306
}
×
307

308
void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connection)
1,454✔
309
{
310
    if (_message_logging_on) {
1,454✔
311
        LogDebug() << "Processing message " << message.msgid << " from "
×
312
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
313
    }
314

315
    // This is a low level interface where incoming messages can be tampered
316
    // with or even dropped.
317
    {
318
        std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
1,454✔
319
        if (_intercept_incoming_messages_callback != nullptr) {
1,454✔
320
            bool keep = _intercept_incoming_messages_callback(message);
241✔
321
            if (!keep) {
241✔
322
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
41✔
323
                return;
41✔
324
            }
325
        }
326
    }
327

328
    /** @note: Forward message if option is enabled and multiple interfaces are connected.
329
     *  Performs message forwarding checks for every messages if message forwarding
330
     *  is enabled on at least one connection, and in case of a single forwarding connection,
331
     *  we check that it is not the one which received the current message.
332
     *
333
     * Conditions:
334
     * 1. At least 2 connections.
335
     * 2. At least 1 forwarding connection.
336
     * 3. At least 2 forwarding connections or current connection is not forwarding.
337
     */
338
    if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
1,413✔
339
        (mavsdk::Connection::forwarding_connections_count() > 1 ||
×
340
         !connection->should_forward_messages())) {
×
341
        if (_message_logging_on) {
×
342
            LogDebug() << "Forwarding message " << message.msgid << " from "
×
343
                       << static_cast<int>(message.sysid) << "/"
×
344
                       << static_cast<int>(message.compid);
×
345
        }
346
        forward_message(message, connection);
×
347
    }
348

349
    // Don't ever create a system with sysid 0.
350
    if (message.sysid == 0) {
1,413✔
351
        if (_message_logging_on) {
×
352
            LogDebug() << "Ignoring message with sysid == 0";
×
353
        }
354
        return;
×
355
    }
356

357
    // Filter out messages by QGroundControl, however, only do that if MAVSDK
358
    // is also implementing a ground station and not if it is used in another
359
    // configuration, e.g. on a companion.
360
    //
361
    // This is a workaround because PX4 started forwarding messages between
362
    // mavlink instances which leads to existing implementations (including
363
    // examples and integration tests) to connect to QGroundControl by accident
364
    // instead of PX4 because the check `has_autopilot()` is not used.
365
    if (_configuration.get_component_type() == Mavsdk::ComponentType::GroundStation &&
1,413✔
366
        message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
1,413✔
367
        if (_message_logging_on) {
×
368
            LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
369
        }
370
        return;
×
371
    }
372

373
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
1,413✔
374

375
    // The only situation where we create a system with sysid 0 is when we initialize the connection
376
    // to the remote.
377
    if (_systems.size() == 1 && _systems[0].first == 0) {
1,413✔
378
        LogDebug() << "New: System ID: " << static_cast<int>(message.sysid)
102✔
379
                   << " Comp ID: " << static_cast<int>(message.compid);
102✔
380
        _systems[0].first = message.sysid;
34✔
381
        _systems[0].second->system_impl()->set_system_id(message.sysid);
34✔
382

383
        // Even though the fake system was already discovered, we can now
384
        // send a notification, now that it seems to really actually exist.
385
        notify_on_discover();
34✔
386
    }
387

388
    bool found_system = false;
1,413✔
389
    for (auto& system : _systems) {
1,413✔
390
        if (system.first == message.sysid) {
1,379✔
391
            system.second->system_impl()->add_new_component(message.compid);
1,379✔
392
            found_system = true;
1,379✔
393
            break;
1,379✔
394
        }
395
    }
396

397
    if (!found_system && message.compid == MAV_COMP_ID_TELEMETRY_RADIO) {
1,413✔
398
        if (_message_logging_on) {
×
399
            LogDebug() << "Don't create new system just for telemetry radio";
×
400
        }
401
        return;
×
402
    }
403

404
    if (!found_system) {
1,413✔
405
        make_system_with_component(message.sysid, message.compid);
34✔
406
    }
407

408
    if (_should_exit) {
1,413✔
409
        // Don't try to call at() if systems have already been destroyed
410
        // in destructor.
411
        return;
1✔
412
    }
413

414
    mavlink_message_handler.process_message(message);
1,412✔
415

416
    for (auto& system : _systems) {
1,412✔
417
        if (system.first == message.sysid) {
1,412✔
418
            system.second->system_impl()->process_mavlink_message(message);
1,412✔
419
            break;
1,412✔
420
        }
421
    }
422
}
423

424
bool MavsdkImpl::send_message(mavlink_message_t& message)
1,569✔
425
{
426
    if (_message_logging_on) {
1,569✔
427
        LogDebug() << "Sending message " << message.msgid << " from "
×
428
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid)
×
429
                   << " to " << static_cast<int>(get_target_system_id(message)) << "/"
×
430
                   << static_cast<int>(get_target_component_id(message));
×
431
    }
432

433
    // This is a low level interface where outgoing messages can be tampered
434
    // with or even dropped.
435
    if (_intercept_outgoing_messages_callback != nullptr) {
1,569✔
436
        const bool keep = _intercept_outgoing_messages_callback(message);
217✔
437
        if (!keep) {
217✔
438
            // We fake that everything was sent as instructed because
439
            // a potential loss would happen later, and we would not be informed
440
            // about it.
441
            LogDebug() << "Dropped outgoing message: " << int(message.msgid);
79✔
442
            return true;
79✔
443
        }
444
    }
445

446
    std::lock_guard<std::mutex> lock(_connections_mutex);
2,980✔
447

448
    if (_connections.empty()) {
1,490✔
449
        // We obviously can't send any messages without a connection added, so
450
        // we silently ignore this.
451
        return true;
34✔
452
    }
453

454
    uint8_t successful_emissions = 0;
1,456✔
455
    for (auto& _connection : _connections) {
2,912✔
456
        const uint8_t target_system_id = get_target_system_id(message);
1,456✔
457

458
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
1,456✔
459
            continue;
×
460
        }
461

462
        if ((*_connection.connection).send_message(message)) {
1,456✔
463
            successful_emissions++;
1,456✔
464
        }
465
    }
466

467
    if (successful_emissions == 0) {
1,456✔
468
        LogErr() << "Sending message failed";
×
469
        return false;
×
470
    }
471

472
    return true;
1,456✔
473
}
474

475
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
68✔
476
    const std::string& connection_url, ForwardingOption forwarding_option)
477
{
478
    CliArg cli_arg;
136✔
479
    if (!cli_arg.parse(connection_url)) {
68✔
480
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
481
    }
482

483
    switch (cli_arg.get_protocol()) {
68✔
484
        case CliArg::Protocol::Udp: {
68✔
485
            int port = cli_arg.get_port() ? cli_arg.get_port() : Mavsdk::DEFAULT_UDP_PORT;
68✔
486

487
            if (cli_arg.get_path().empty() || cli_arg.get_path() == Mavsdk::DEFAULT_UDP_BIND_IP) {
68✔
488
                std::string path = Mavsdk::DEFAULT_UDP_BIND_IP;
102✔
489
                return add_udp_connection(path, port, forwarding_option);
34✔
490
            } else {
491
                std::string path = cli_arg.get_path();
68✔
492
                return setup_udp_remote(path, port, forwarding_option);
34✔
493
            }
494
        }
495

496
        case CliArg::Protocol::Tcp: {
×
497
            std::string path = Mavsdk::DEFAULT_TCP_REMOTE_IP;
×
498
            int port = Mavsdk::DEFAULT_TCP_REMOTE_PORT;
×
499
            if (!cli_arg.get_path().empty()) {
×
500
                path = cli_arg.get_path();
×
501
            }
502
            if (cli_arg.get_port()) {
×
503
                port = cli_arg.get_port();
×
504
            }
505
            return add_tcp_connection(path, port, forwarding_option);
×
506
        }
507

508
        case CliArg::Protocol::Serial: {
×
509
            int baudrate = Mavsdk::DEFAULT_SERIAL_BAUDRATE;
×
510
            if (cli_arg.get_baudrate()) {
×
511
                baudrate = cli_arg.get_baudrate();
×
512
            }
513
            bool flow_control = cli_arg.get_flow_control();
×
514
            return add_serial_connection(
515
                cli_arg.get_path(), baudrate, flow_control, forwarding_option);
×
516
        }
517

518
        default:
×
519
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
520
    }
521
}
522

523
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_udp_connection(
34✔
524
    const std::string& local_ip, const int local_port, ForwardingOption forwarding_option)
525
{
526
    auto new_conn = std::make_shared<UdpConnection>(
34✔
527
        [this](mavlink_message_t& message, Connection* connection) {
888✔
528
            receive_message(message, connection);
888✔
529
        },
888✔
530
        local_ip,
531
        local_port,
532
        forwarding_option);
68✔
533
    if (!new_conn) {
34✔
534
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
535
    }
536
    ConnectionResult ret = new_conn->start();
34✔
537
    if (ret == ConnectionResult::Success) {
34✔
538
        return {ret, add_connection(new_conn)};
34✔
539
    } else {
540
        return {ret, Mavsdk::ConnectionHandle{}};
×
541
    }
542
}
543

544
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::setup_udp_remote(
34✔
545
    const std::string& remote_ip, int remote_port, ForwardingOption forwarding_option)
546
{
547
    auto new_conn = std::make_shared<UdpConnection>(
34✔
548
        [this](mavlink_message_t& message, Connection* connection) {
566✔
549
            receive_message(message, connection);
566✔
550
        },
566✔
551
        "0.0.0.0",
552
        0,
34✔
553
        forwarding_option);
68✔
554
    if (!new_conn) {
34✔
555
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
556
    }
557
    ConnectionResult ret = new_conn->start();
34✔
558
    if (ret == ConnectionResult::Success) {
34✔
559
        new_conn->add_remote(remote_ip, remote_port);
34✔
560
        auto handle = add_connection(new_conn);
34✔
561
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
68✔
562
        if (_systems.empty()) {
34✔
563
            make_system_with_component(0, 0);
34✔
564
        }
565

566
        // With a UDP remote, we need to initiate the connection by sending
567
        // heartbeats.
568
        auto new_configuration = get_configuration();
34✔
569
        new_configuration.set_always_send_heartbeats(true);
34✔
570
        set_configuration(new_configuration);
34✔
571

572
        return {ret, handle};
34✔
573
    } else {
574
        return {ret, Mavsdk::ConnectionHandle{}};
×
575
    }
576
}
577

578
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_tcp_connection(
×
579
    const std::string& remote_ip, int remote_port, ForwardingOption forwarding_option)
580
{
581
    auto new_conn = std::make_shared<TcpConnection>(
×
582
        [this](mavlink_message_t& message, Connection* connection) {
×
583
            receive_message(message, connection);
×
584
        },
×
585
        remote_ip,
586
        remote_port,
587
        forwarding_option);
×
588
    if (!new_conn) {
×
589
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
590
    }
591
    ConnectionResult ret = new_conn->start();
×
592
    if (ret == ConnectionResult::Success) {
×
593
        return {ret, add_connection(new_conn)};
×
594
    } else {
595
        return {ret, Mavsdk::ConnectionHandle{}};
×
596
    }
597
}
598

599
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
600
    const std::string& dev_path,
601
    int baudrate,
602
    bool flow_control,
603
    ForwardingOption forwarding_option)
604
{
605
    auto new_conn = std::make_shared<SerialConnection>(
×
606
        [this](mavlink_message_t& message, Connection* connection) {
×
607
            receive_message(message, connection);
×
608
        },
×
609
        dev_path,
610
        baudrate,
611
        flow_control,
612
        forwarding_option);
×
613
    if (!new_conn) {
×
614
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
615
    }
616
    ConnectionResult ret = new_conn->start();
×
617
    if (ret == ConnectionResult::Success) {
×
618
        auto handle = add_connection(new_conn);
×
619

620
        auto new_configuration = get_configuration();
×
621

622
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
623
        // to initiate the MAVLink connection by sending heartbeats.
624
        // Therefore, we override the default here and enable sending heartbeats.
625
        new_configuration.set_always_send_heartbeats(true);
×
626
        set_configuration(new_configuration);
×
627

628
        return {ret, handle};
×
629

630
    } else {
631
        return {ret, Mavsdk::ConnectionHandle{}};
×
632
    }
633
}
634

635
Mavsdk::ConnectionHandle
636
MavsdkImpl::add_connection(const std::shared_ptr<Connection>& new_connection)
68✔
637
{
638
    std::lock_guard<std::mutex> lock(_connections_mutex);
68✔
639
    auto handle = Mavsdk::ConnectionHandle{_connections_handle_id++};
68✔
640
    _connections.emplace_back(ConnectionEntry{new_connection, handle});
68✔
641

642
    return handle;
68✔
643
}
644

645
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
×
646
{
647
    std::lock_guard<std::mutex> lock(_connections_mutex);
×
648

649
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
×
650
        return (entry.handle == handle);
×
651
    }));
×
652
}
×
653

654
Mavsdk::Configuration MavsdkImpl::get_configuration() const
34✔
655
{
656
    return _configuration;
34✔
657
}
658

659
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
103✔
660
{
661
    // We just point the default to the newly created component. This means
662
    // that the previous default component will be deleted if it is not
663
    // used/referenced anywhere.
664
    _default_server_component = server_component_by_id(new_configuration.get_component_id());
103✔
665

666
    if (new_configuration.get_always_send_heartbeats() &&
171✔
667
        !_configuration.get_always_send_heartbeats()) {
68✔
668
        start_sending_heartbeats();
34✔
669
    } else if (
69✔
670
        !new_configuration.get_always_send_heartbeats() &&
104✔
671
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
104✔
672
        stop_sending_heartbeats();
×
673
    }
674

675
    _configuration = new_configuration;
103✔
676
}
103✔
677

678
uint8_t MavsdkImpl::get_own_system_id() const
3,979✔
679
{
680
    return _configuration.get_system_id();
3,979✔
681
}
682

683
uint8_t MavsdkImpl::get_own_component_id() const
1,139✔
684
{
685
    return _configuration.get_component_id();
1,139✔
686
}
687

688
uint8_t MavsdkImpl::channel() const
×
689
{
690
    // TODO
691
    return 0;
×
692
}
693

694
Autopilot MavsdkImpl::autopilot() const
×
695
{
696
    // TODO
697
    return Autopilot::Px4;
×
698
}
699

700
// FIXME: this should be per component
701
uint8_t MavsdkImpl::get_mav_type() const
124✔
702
{
703
    switch (_configuration.get_component_type()) {
124✔
704
        case Mavsdk::ComponentType::Autopilot:
80✔
705
            return MAV_TYPE_GENERIC;
80✔
706

707
        case Mavsdk::ComponentType::GroundStation:
42✔
708
            return MAV_TYPE_GCS;
42✔
709

710
        case Mavsdk::ComponentType::CompanionComputer:
×
711
            return MAV_TYPE_ONBOARD_CONTROLLER;
×
712

713
        case Mavsdk::ComponentType::Camera:
2✔
714
            return MAV_TYPE_CAMERA;
2✔
715

716
        case Mavsdk::ComponentType::Custom:
×
717
            return MAV_TYPE_GENERIC;
×
718

719
        default:
×
720
            LogErr() << "Unknown configuration";
×
721
            return 0;
×
722
    }
723
}
724

725
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
68✔
726
{
727
    // Needs _systems_lock
728

729
    if (_should_exit) {
68✔
730
        // When the system got destroyed in the destructor, we have to give up.
731
        return;
×
732
    }
733

734
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
68✔
735
        LogDebug() << "Initializing connection to remote system...";
34✔
736
    } else {
737
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
102✔
738
                   << " Comp ID: " << static_cast<int>(comp_id);
102✔
739
    }
740

741
    // Make a system with its first component
742
    auto new_system = std::make_shared<System>(*this);
136✔
743
    new_system->init(system_id, comp_id);
68✔
744

745
    _systems.emplace_back(system_id, new_system);
68✔
746
}
747

748
void MavsdkImpl::notify_on_discover()
101✔
749
{
750
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
202✔
751
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
135✔
752
}
101✔
753

754
void MavsdkImpl::notify_on_timeout()
×
755
{
756
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
×
757
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
758
}
×
759

760
Mavsdk::NewSystemHandle
761
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
34✔
762
{
763
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
34✔
764

765
    const auto handle = _new_system_callbacks.subscribe(callback);
34✔
766

767
    if (is_any_system_connected()) {
34✔
768
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
769
    }
770

771
    return handle;
34✔
772
}
773

774
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
34✔
775
{
776
    _new_system_callbacks.unsubscribe(handle);
34✔
777
}
34✔
778

779
bool MavsdkImpl::is_any_system_connected() const
34✔
780
{
781
    std::vector<std::shared_ptr<System>> connected_systems = systems();
68✔
782
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
34✔
783
        return system->is_connected();
×
784
    });
34✔
785
}
786

787
void MavsdkImpl::work_thread()
11,380✔
788
{
789
    while (!_should_exit) {
11,380✔
790
        timeout_handler.run_once();
11,007✔
791
        call_every_handler.run_once();
11,311✔
792

793
        {
794
            std::lock_guard<std::mutex> lock(_server_components_mutex);
22,431✔
795
            for (auto& it : _server_components) {
22,663✔
796
                if (it.second != nullptr) {
11,448✔
797
                    it.second->_impl->do_work();
11,447✔
798
                }
799
            }
800
        }
801

802
        std::this_thread::sleep_for(std::chrono::milliseconds(10));
11,217✔
803
    }
804
}
64✔
805

806
void MavsdkImpl::call_user_callback_located(
766✔
807
    const std::string& filename, const int linenumber, const std::function<void()>& func)
808
{
809
    auto callback_size = _user_callback_queue.size();
766✔
810
    if (callback_size == 10) {
766✔
UNCOV
811
        LogWarn()
×
UNCOV
812
            << "User callback queue too slow.\n"
×
UNCOV
813
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
814

815
    } else if (callback_size == 99) {
766✔
816
        LogErr()
×
817
            << "User callback queue overflown\n"
×
818
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
819

820
    } else if (callback_size == 100) {
766✔
821
        return;
×
822
    }
823

824
    // We only need to keep track of filename and linenumber if we're actually debugging this.
825
    UserCallback user_callback =
766✔
826
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
2,298✔
827

828
    _user_callback_queue.enqueue(user_callback);
766✔
829
}
830

831
void MavsdkImpl::process_user_callbacks_thread()
904✔
832
{
833
    while (!_should_exit) {
904✔
834
        auto callback = _user_callback_queue.dequeue();
835✔
835
        if (!callback) {
835✔
836
            continue;
69✔
837
        }
838

839
        void* cookie{nullptr};
766✔
840

841
        const double timeout_s = 1.0;
766✔
842
        timeout_handler.add(
766✔
843
            [&]() {
×
844
                if (_callback_debugging) {
×
845
                    LogWarn() << "Callback called from " << callback.value().filename << ":"
×
846
                              << callback.value().linenumber << " took more than " << timeout_s
×
847
                              << " second to run.";
×
848
                    fflush(stdout);
×
849
                    fflush(stderr);
×
850
                    abort();
×
851
                } else {
852
                    LogWarn()
×
853
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
854
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
855
                }
856
            },
×
857
            timeout_s,
858
            &cookie);
859
        callback.value().func();
766✔
860
        timeout_handler.remove(cookie);
766✔
861
    }
862
}
69✔
863

864
void MavsdkImpl::start_sending_heartbeats()
101✔
865
{
866
    // Before sending out first heartbeats we need to make sure we have a
867
    // default server component.
868
    default_server_component_impl();
101✔
869

870
    if (_heartbeat_send_cookie == nullptr) {
101✔
871
        call_every_handler.add(
68✔
872
            [this]() { send_heartbeat(); }, HEARTBEAT_SEND_INTERVAL_S, &_heartbeat_send_cookie);
124✔
873
    }
874
}
101✔
875

876
void MavsdkImpl::stop_sending_heartbeats()
×
877
{
878
    if (!_configuration.get_always_send_heartbeats()) {
×
879
        call_every_handler.remove(_heartbeat_send_cookie);
×
880
        _heartbeat_send_cookie = nullptr;
×
881
    }
882
}
×
883

884
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
727✔
885
{
886
    if (_default_server_component == nullptr) {
727✔
887
        _default_server_component = server_component_by_id(_configuration.get_component_id());
×
888
    }
889
    return *_default_server_component->_impl;
727✔
890
}
891

892
void MavsdkImpl::send_heartbeat()
124✔
893
{
894
    std::lock_guard<std::mutex> lock(_server_components_mutex);
248✔
895

896
    for (auto& it : _server_components) {
248✔
897
        if (it.second != nullptr) {
124✔
898
            it.second->_impl->send_heartbeat();
124✔
899
        }
900
    }
901
}
124✔
902

903
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
22✔
904
{
905
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
44✔
906
    _intercept_incoming_messages_callback = callback;
22✔
907
}
22✔
908

909
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
910
{
911
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
28✔
912
    _intercept_outgoing_messages_callback = callback;
14✔
913
}
14✔
914

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

920
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
1,456✔
921
        return 0;
191✔
922
    }
923

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

930
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,265✔
931
}
932

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

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

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

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

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

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