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

mavlink / MAVSDK / 17823325850

18 Sep 2025 08:49AM UTC coverage: 47.633% (+0.008%) from 47.625%
17823325850

push

github

web-flow
Merge pull request #2655 from mavlink/pr-mavlink-direct-docs

Add MavlinkDirect docs and more examples

17044 of 35782 relevant lines covered (47.63%)

451.46 hits per line

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

43.8
/src/mavsdk/core/system_impl.cpp
1
#include "system.h"
2
#include "mavsdk_impl.h"
3
#include "mavlink_include.h"
4
#include "system_impl.h"
5
#include <mav/MessageSet.h>
6
#include "server_component_impl.h"
7
#include "plugin_impl_base.h"
8
#include "px4_custom_mode.h"
9
#include "ardupilot_custom_mode.h"
10
#include "callback_list.tpp"
11
#include "unused.h"
12
#include <cassert>
13
#include <cstdlib>
14
#include <functional>
15
#include <future>
16
#include <utility>
17

18
namespace mavsdk {
19

20
template class CallbackList<bool>;
21
template class CallbackList<ComponentType>;
22
template class CallbackList<ComponentType, uint8_t>;
23

24
SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) :
127✔
25
    _mavsdk_impl(mavsdk_impl),
127✔
26
    _command_sender(*this),
127✔
27
    _timesync(*this),
127✔
28
    _ping(*this),
127✔
29
    _mission_transfer_client(
254✔
30
        _mavsdk_impl.default_server_component_impl().sender(),
127✔
31
        _mavlink_message_handler,
127✔
32
        _mavsdk_impl.timeout_handler,
127✔
33
        [this]() { return timeout_s(); },
1✔
34
        [this]() { return autopilot(); }),
1✔
35
    _mavlink_request_message(
127✔
36
        *this, _command_sender, _mavlink_message_handler, _mavsdk_impl.timeout_handler),
127✔
37
    _mavlink_ftp_client(*this),
127✔
38
    _mavlink_component_metadata(*this)
254✔
39
{
40
    if (const char* env_p = std::getenv("MAVSDK_MESSAGE_DEBUGGING")) {
127✔
41
        if (std::string(env_p) == "1") {
×
42
            _message_debugging = true;
×
43
        }
44
    }
45

46
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
127✔
47
}
127✔
48

49
SystemImpl::~SystemImpl()
127✔
50
{
51
    _should_exit = true;
127✔
52
    _mavlink_message_handler.unregister_all(this);
127✔
53
    // Clear all libmav message callbacks
54
    _libmav_message_callbacks.clear();
127✔
55

56
    unregister_timeout_handler(_heartbeat_timeout_cookie);
127✔
57

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

65
void SystemImpl::init(uint8_t system_id, uint8_t comp_id)
127✔
66
{
67
    _target_address.system_id = system_id;
127✔
68
    // We use this as a default.
69
    _target_address.component_id = MAV_COMP_ID_AUTOPILOT1;
127✔
70

71
    _mavlink_message_handler.register_one(
127✔
72
        MAVLINK_MSG_ID_HEARTBEAT,
73
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
306✔
74
        this);
75

76
    _mavlink_message_handler.register_one(
127✔
77
        MAVLINK_MSG_ID_STATUSTEXT,
78
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
79
        this);
80

81
    _mavlink_message_handler.register_one(
127✔
82
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
83
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
59✔
84
        this);
85

86
    add_new_component(comp_id);
127✔
87
}
127✔
88

89
bool SystemImpl::is_connected() const
62✔
90
{
91
    return _connected;
62✔
92
}
93

94
void SystemImpl::register_mavlink_message_handler(
601✔
95
    uint16_t msg_id, const MavlinkMessageHandler::Callback& callback, const void* cookie)
96
{
97
    _mavlink_message_handler.register_one(msg_id, callback, cookie);
601✔
98
}
601✔
99

100
void SystemImpl::register_mavlink_message_handler_with_compid(
×
101
    uint16_t msg_id,
102
    uint8_t component_id,
103
    const MavlinkMessageHandler::Callback& callback,
104
    const void* cookie)
105
{
106
    _mavlink_message_handler.register_one_with_component_id(msg_id, component_id, callback, cookie);
×
107
}
×
108

109
void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
110
{
111
    _mavlink_message_handler.unregister_one(msg_id, cookie);
×
112
}
×
113

114
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
525✔
115
{
116
    _mavlink_message_handler.unregister_all(cookie);
525✔
117
}
525✔
118

119
void SystemImpl::update_component_id_messages_handler(
×
120
    uint16_t msg_id, uint8_t component_id, const void* cookie)
121
{
122
    _mavlink_message_handler.update_component_id(msg_id, component_id, cookie);
×
123
}
×
124

125
void SystemImpl::process_libmav_message(const Mavsdk::MavlinkMessage& message)
2,406✔
126
{
127
    if (_message_debugging) {
2,406✔
128
        LogDebug() << "SystemImpl::process_libmav_message: " << message.message_name;
×
129
    }
130

131
    // CallbackList handles thread safety - just call all callbacks and let them filter internally
132
    _libmav_message_callbacks.queue(
2,406✔
133
        message, [this](const std::function<void()>& callback_wrapper) { callback_wrapper(); });
53✔
134
}
2,403✔
135

136
Handle<Mavsdk::MavlinkMessage> SystemImpl::register_libmav_message_handler(
24✔
137
    const std::string& message_name, const LibmavMessageCallback& callback)
138
{
139
    // Create a filtering callback that only calls the user callback for matching messages
140
    auto filtering_callback =
141
        [this, message_name, callback](const Mavsdk::MavlinkMessage& message) {
106✔
142
            if (_message_debugging) {
53✔
143
                LogDebug() << "Checking handler for message: '" << message_name << "' against '"
×
144
                           << message.message_name << "'";
×
145
            }
146

147
            // Check if message name matches (empty string means match all messages)
148
            if (!message_name.empty() && message_name != message.message_name) {
53✔
149
                if (_message_debugging) {
×
150
                    LogDebug() << "Handler message name mismatch, skipping";
×
151
                }
152
                return;
×
153
            }
154

155
            // Call the user callback
156
            if (_message_debugging) {
53✔
157
                LogDebug() << "Calling libmav handler for: " << message.message_name;
×
158
            }
159
            callback(message);
53✔
160
        };
24✔
161

162
    auto handle = _libmav_message_callbacks.subscribe(filtering_callback);
24✔
163

164
    if (_message_debugging) {
24✔
165
        LogDebug() << "Registering libmav handler for message: '" << message_name << "'";
×
166
    }
167

168
    return handle;
48✔
169
}
24✔
170

171
Handle<Mavsdk::MavlinkMessage> SystemImpl::register_libmav_message_handler_with_compid(
×
172
    const std::string& message_name, uint8_t cmp_id, const LibmavMessageCallback& callback)
173
{
174
    // Create a filtering callback that only calls the user callback for matching messages
175
    auto filtering_callback =
176
        [this, message_name, cmp_id, callback](const Mavsdk::MavlinkMessage& message) {
×
177
            if (_message_debugging) {
×
178
                LogDebug() << "Checking handler for message: '" << message_name << "' against '"
×
179
                           << message.message_name
×
180
                           << "' with component ID: " << static_cast<int>(cmp_id);
×
181
            }
182

183
            // Check if message name matches (empty string means match all messages)
184
            if (!message_name.empty() && message_name != message.message_name) {
×
185
                if (_message_debugging) {
×
186
                    LogDebug() << "Handler message name mismatch, skipping";
×
187
                }
188
                return;
×
189
            }
190

191
            // Check if component ID matches
192
            if (cmp_id != message.component_id) {
×
193
                if (_message_debugging) {
×
194
                    LogDebug() << "Handler component ID mismatch, skipping";
×
195
                }
196
                return;
×
197
            }
198

199
            // Call the user callback
200
            if (_message_debugging) {
×
201
                LogDebug() << "Calling libmav handler for: " << message.message_name;
×
202
            }
203
            callback(message);
×
204
        };
×
205

206
    auto handle = _libmav_message_callbacks.subscribe(filtering_callback);
×
207

208
    if (_message_debugging) {
×
209
        LogDebug() << "Registering libmav handler for message: '" << message_name
×
210
                   << "' with component ID: " << static_cast<int>(cmp_id);
×
211
    }
212

213
    return handle;
×
214
}
×
215

216
void SystemImpl::unregister_libmav_message_handler(Handle<Mavsdk::MavlinkMessage> handle)
24✔
217
{
218
    _libmav_message_callbacks.unsubscribe(handle);
24✔
219

220
    if (_message_debugging) {
24✔
221
        LogDebug() << "Unregistered libmav handler";
×
222
    }
223
}
24✔
224

225
TimeoutHandler::Cookie
226
SystemImpl::register_timeout_handler(const std::function<void()>& callback, double duration_s)
1,181✔
227
{
228
    return _mavsdk_impl.timeout_handler.add(callback, duration_s);
1,181✔
229
}
230

231
void SystemImpl::refresh_timeout_handler(TimeoutHandler::Cookie cookie)
180✔
232
{
233
    _mavsdk_impl.timeout_handler.refresh(cookie);
180✔
234
}
176✔
235

236
void SystemImpl::unregister_timeout_handler(TimeoutHandler::Cookie cookie)
1,368✔
237
{
238
    _mavsdk_impl.timeout_handler.remove(cookie);
1,368✔
239
}
1,368✔
240

241
double SystemImpl::timeout_s() const
1,137✔
242
{
243
    return _mavsdk_impl.timeout_s();
1,137✔
244
}
245

246
void SystemImpl::enable_timesync()
×
247
{
248
    _timesync.enable();
×
249
}
×
250

251
System::IsConnectedHandle
252
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
253
{
254
    return _is_connected_callbacks.subscribe(callback);
×
255
}
256

257
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
258
{
259
    _is_connected_callbacks.unsubscribe(handle);
×
260
}
×
261

262
void SystemImpl::process_mavlink_message(mavlink_message_t& message)
2,368✔
263
{
264
    _mavlink_message_handler.process_message(message);
2,368✔
265
}
2,373✔
266

267
CallEveryHandler::Cookie
268
SystemImpl::add_call_every(std::function<void()> callback, float interval_s)
33✔
269
{
270
    return _mavsdk_impl.call_every_handler.add(
66✔
271
        std::move(callback), static_cast<double>(interval_s));
66✔
272
}
273

274
void SystemImpl::change_call_every(float interval_s, CallEveryHandler::Cookie cookie)
×
275
{
276
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
277
}
×
278

279
void SystemImpl::reset_call_every(CallEveryHandler::Cookie cookie)
×
280
{
281
    _mavsdk_impl.call_every_handler.reset(cookie);
×
282
}
×
283

284
void SystemImpl::remove_call_every(CallEveryHandler::Cookie cookie)
33✔
285
{
286
    _mavsdk_impl.call_every_handler.remove(cookie);
33✔
287
}
33✔
288

289
void SystemImpl::register_statustext_handler(
6✔
290
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
291
{
292
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
6✔
293
}
6✔
294

295
void SystemImpl::unregister_statustext_handler(void* cookie)
6✔
296
{
297
    _statustext_handler_callbacks.erase(std::remove_if(
6✔
298
        _statustext_handler_callbacks.begin(),
299
        _statustext_handler_callbacks.end(),
300
        [&](const auto& entry) { return entry.cookie == cookie; }));
6✔
301
}
6✔
302

303
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
306✔
304
{
305
    mavlink_heartbeat_t heartbeat;
306
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
306✔
307

308
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
305✔
309
        _autopilot = Autopilot::Px4;
×
310
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
305✔
311
        _autopilot = Autopilot::ArduPilot;
5✔
312
    }
313

314
    // Only set the vehicle type if the heartbeat is from an autopilot component
315
    // This check only works if the MAV_TYPE::MAV_TYPE_ENUM_END is actually the
316
    // last enumerator.
317
    if (MAV_TYPE::MAV_TYPE_ENUM_END < heartbeat.type) {
303✔
318
        LogErr() << "type received in HEARTBEAT was not recognized";
×
319
    } else {
320
        const auto new_vehicle_type = static_cast<MAV_TYPE>(heartbeat.type);
303✔
321
        if (heartbeat.autopilot != MAV_AUTOPILOT_INVALID && _vehicle_type != new_vehicle_type &&
303✔
322
            new_vehicle_type != MAV_TYPE_GENERIC) {
323
            LogWarn() << "Vehicle type changed (new type: " << static_cast<unsigned>(heartbeat.type)
3✔
324
                      << ", old type: " << static_cast<unsigned>(_vehicle_type) << ")";
3✔
325
            _vehicle_type = new_vehicle_type;
3✔
326
        }
327
    }
328

329
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
303✔
330
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
145✔
331
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
145✔
332
    }
333
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
305✔
334
        _flight_mode =
5✔
335
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
336
    }
337

338
    set_connected();
305✔
339
}
306✔
340

341
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
342
{
343
    mavlink_statustext_t statustext;
344
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
345

346
    const auto maybe_result = _statustext_handler.process(statustext);
3✔
347

348
    if (maybe_result.has_value()) {
3✔
349
        LogDebug() << "MAVLink: "
3✔
350
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
351
                   << maybe_result.value().text;
3✔
352

353
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
354
            entry.callback(maybe_result.value());
3✔
355
        }
356
    }
357
}
3✔
358

359
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
59✔
360
{
361
    mavlink_autopilot_version_t autopilot_version;
362
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
59✔
363

364
    _mission_transfer_client.set_int_messages_supported(
59✔
365
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
59✔
366
}
59✔
367

368
void SystemImpl::heartbeats_timed_out()
×
369
{
370
    LogInfo() << "heartbeats timed out";
×
371
    set_disconnected();
×
372
}
×
373

374
void SystemImpl::system_thread()
127✔
375
{
376
    SteadyTimePoint last_ping_time{};
127✔
377

378
    while (!_should_exit) {
12,976✔
379
        {
380
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
12,725✔
381
            for (auto& entry : _mavlink_parameter_clients) {
13,745✔
382
                entry.parameter_client->do_work();
1,085✔
383
            }
384
        }
12,564✔
385
        _command_sender.do_work();
12,789✔
386
        _timesync.do_work();
12,675✔
387
        _mission_transfer_client.do_work();
12,671✔
388
        _mavlink_ftp_client.do_work();
12,733✔
389

390
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
12,724✔
391
            if (_connected && _autopilot != Autopilot::ArduPilot) {
129✔
392
                _ping.run_once();
13✔
393
            }
394
            last_ping_time = _mavsdk_impl.time.steady_time();
129✔
395
        }
396

397
        if (_connected) {
12,574✔
398
            // Work fairly fast if we're connected.
399
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
12,454✔
400
        } else {
401
            // Be less aggressive when unconnected.
402
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
116✔
403
        }
404
    }
405
}
126✔
406

407
std::string SystemImpl::component_name(uint8_t component_id)
130✔
408
{
409
    switch (component_id) {
130✔
410
        case MAV_COMP_ID_AUTOPILOT1:
52✔
411
            return "Autopilot";
52✔
412
        case MAV_COMP_ID_CAMERA:
9✔
413
            return "Camera 1";
9✔
414
        case MAV_COMP_ID_CAMERA2:
×
415
            return "Camera 2";
×
416
        case MAV_COMP_ID_CAMERA3:
×
417
            return "Camera 3";
×
418
        case MAV_COMP_ID_CAMERA4:
×
419
            return "Camera 4";
×
420
        case MAV_COMP_ID_CAMERA5:
×
421
            return "Camera 5";
×
422
        case MAV_COMP_ID_CAMERA6:
×
423
            return "Camera 6";
×
424
        case MAV_COMP_ID_GIMBAL:
×
425
            return "Gimbal";
×
426
        case MAV_COMP_ID_MISSIONPLANNER:
63✔
427
            return "Ground station";
63✔
428
        case MAV_COMP_ID_ONBOARD_COMPUTER:
1✔
429
            return "Companion Computer";
1✔
430
        case MAV_COMP_ID_WINCH:
×
431
            return "Winch";
×
432
        default:
5✔
433
            return "Unsupported component";
5✔
434
    }
435
}
436

437
ComponentType SystemImpl::component_type(uint8_t component_id)
260✔
438
{
439
    switch (component_id) {
260✔
440
        case MAV_COMP_ID_AUTOPILOT1:
104✔
441
            return ComponentType::Autopilot;
104✔
442
        case MAV_COMP_ID_MISSIONPLANNER:
126✔
443
            return ComponentType::GroundStation;
126✔
444
        case MAV_COMP_ID_ONBOARD_COMPUTER:
2✔
445
        case MAV_COMP_ID_ONBOARD_COMPUTER2:
446
        case MAV_COMP_ID_ONBOARD_COMPUTER3:
447
        case MAV_COMP_ID_ONBOARD_COMPUTER4:
448
            return ComponentType::CompanionComputer;
2✔
449
        case MAV_COMP_ID_CAMERA:
18✔
450
        case MAV_COMP_ID_CAMERA2:
451
        case MAV_COMP_ID_CAMERA3:
452
        case MAV_COMP_ID_CAMERA4:
453
        case MAV_COMP_ID_CAMERA5:
454
        case MAV_COMP_ID_CAMERA6:
455
            return ComponentType::Camera;
18✔
456
        case MAV_COMP_ID_GIMBAL:
×
457
            return ComponentType::Gimbal;
×
458
        case MAV_COMP_ID_ODID_TXRX_1:
×
459
        case MAV_COMP_ID_ODID_TXRX_2:
460
        case MAV_COMP_ID_ODID_TXRX_3:
461
            return ComponentType::RemoteId;
×
462
        default:
10✔
463
            return ComponentType::Custom;
10✔
464
    }
465
}
466

467
void SystemImpl::add_new_component(uint8_t component_id)
4,770✔
468
{
469
    if (component_id == 0) {
4,770✔
470
        return;
×
471
    }
472

473
    bool is_new_component = false;
4,770✔
474
    {
475
        std::lock_guard<std::mutex> lock(_components_mutex);
4,770✔
476
        auto res_pair = _components.insert(component_id);
4,776✔
477
        is_new_component = res_pair.second;
4,776✔
478
    }
4,776✔
479

480
    if (is_new_component) {
4,777✔
481
        _component_discovered_callbacks.queue(
130✔
482
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
483
        _component_discovered_id_callbacks.queue(
130✔
484
            component_type(component_id), component_id, [this](const auto& func) {
×
485
                call_user_callback(func);
×
486
            });
×
487
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
260✔
488
                   << ") added.";
130✔
489
    }
490
}
491

492
size_t SystemImpl::total_components() const
×
493
{
494
    std::lock_guard<std::mutex> lock(_components_mutex);
×
495
    return _components.size();
×
496
}
×
497

498
System::ComponentDiscoveredHandle
499
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
500
{
501
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
502

503
    if (total_components() > 0) {
×
504
        std::lock_guard<std::mutex> components_lock(_components_mutex);
×
505
        for (const auto& elem : _components) {
×
506
            _component_discovered_callbacks.queue(
×
507
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
508
        }
509
    }
×
510
    return handle;
×
511
}
512

513
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
514
{
515
    _component_discovered_callbacks.unsubscribe(handle);
×
516
}
×
517

518
System::ComponentDiscoveredIdHandle
519
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
520
{
521
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
522

523
    if (total_components() > 0) {
×
524
        std::lock_guard<std::mutex> components_lock(_components_mutex);
×
525
        for (const auto& elem : _components) {
×
526
            _component_discovered_id_callbacks.queue(
×
527
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
528
        }
529
    }
×
530
    return handle;
×
531
}
532

533
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
534
{
535
    _component_discovered_id_callbacks.unsubscribe(handle);
×
536
}
×
537

538
bool SystemImpl::is_standalone() const
×
539
{
540
    return !has_autopilot();
×
541
}
542

543
bool SystemImpl::has_autopilot() const
230✔
544
{
545
    return get_autopilot_id() != uint8_t(0);
230✔
546
}
547

548
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
549
{
550
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
551
}
552

553
bool SystemImpl::is_camera(uint8_t comp_id)
9✔
554
{
555
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
9✔
556
}
557

558
bool SystemImpl::has_camera(int camera_id) const
9✔
559
{
560
    std::lock_guard<std::mutex> lock(_components_mutex);
9✔
561
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
9✔
562

563
    if (camera_comp_id == -1) { // Check whether the system has any camera.
9✔
564
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
9✔
565
            return true;
9✔
566
        }
567
    } else { // Look for the camera whose id is `camera_id`.
568
        for (auto compid : _components) {
×
569
            if (compid == camera_comp_id) {
×
570
                return true;
×
571
            }
572
        }
573
    }
574
    return false;
×
575
}
9✔
576

577
bool SystemImpl::has_gimbal() const
×
578
{
579
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
580
}
581

582
bool SystemImpl::send_message(mavlink_message_t& message)
×
583
{
584
    return _mavsdk_impl.send_message(message);
×
585
}
586

587
bool SystemImpl::queue_message(
858✔
588
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
589
{
590
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
858✔
591
}
592

593
void SystemImpl::send_autopilot_version_request()
52✔
594
{
595
    mavlink_request_message().request(
52✔
596
        MAVLINK_MSG_ID_AUTOPILOT_VERSION, MAV_COMP_ID_AUTOPILOT1, nullptr);
597
}
52✔
598

599
void SystemImpl::set_connected()
305✔
600
{
601
    bool enable_needed = false;
305✔
602
    {
603
        if (!_connected) {
305✔
604
            {
605
                std::lock_guard<std::mutex> lock(_components_mutex);
126✔
606
                if (!_components.empty()) {
127✔
607
                    LogDebug() << "Discovered " << _components.size() << " component(s)";
127✔
608
                }
609
            }
127✔
610

611
            _connected = true;
127✔
612

613
            // Only send heartbeats if we're not shutting down
614
            if (!_should_exit) {
127✔
615
                // We call this later to avoid deadlocks on creating the server components.
616
                _mavsdk_impl.call_user_callback([this]() {
254✔
617
                    // Send a heartbeat back immediately.
618
                    _mavsdk_impl.start_sending_heartbeats();
619
                });
620
            }
621

622
            _heartbeat_timeout_cookie =
127✔
623
                register_timeout_handler([this] { heartbeats_timed_out(); }, HEARTBEAT_TIMEOUT_S);
127✔
624

625
            enable_needed = true;
127✔
626

627
            // Queue callbacks without holding any locks to avoid deadlocks
628
            _is_connected_callbacks.queue(
127✔
629
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
630

631
        } else if (_connected) {
178✔
632
            refresh_timeout_handler(_heartbeat_timeout_cookie);
179✔
633
        }
634
        // If not yet connected there is nothing to do
635
    }
636

637
    if (enable_needed) {
304✔
638
        // Notify about the new system without holding any locks
639
        _mavsdk_impl.notify_on_discover();
127✔
640

641
        if (has_autopilot()) {
127✔
642
            send_autopilot_version_request();
52✔
643
        }
644

645
        // Enable plugins
646
        std::vector<PluginImplBase*> plugin_impls_to_enable;
127✔
647
        {
648
            std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
127✔
649
            plugin_impls_to_enable = _plugin_impls;
127✔
650
        }
127✔
651

652
        for (auto plugin_impl : plugin_impls_to_enable) {
127✔
653
            plugin_impl->enable();
×
654
        }
655
    }
127✔
656
}
304✔
657

658
void SystemImpl::set_disconnected()
×
659
{
660
    {
661
        // This might not be needed because this is probably called from the triggered
662
        // timeout anyway, but it should also do no harm.
663
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
664
        //_heartbeat_timeout_cookie = nullptr;
665

666
        _connected = false;
×
667
        _is_connected_callbacks.queue(
×
668
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
669
    }
670
    _mavsdk_impl.notify_on_timeout();
×
671

672
    _mavsdk_impl.stop_sending_heartbeats();
×
673

674
    {
675
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
676
        for (auto plugin_impl : _plugin_impls) {
×
677
            plugin_impl->disable();
×
678
        }
679
    }
×
680
}
×
681

682
uint8_t SystemImpl::get_system_id() const
819✔
683
{
684
    return _target_address.system_id;
819✔
685
}
686

687
std::vector<uint8_t> SystemImpl::component_ids() const
11✔
688
{
689
    std::lock_guard<std::mutex> lock(_components_mutex);
11✔
690
    return std::vector<uint8_t>{_components.begin(), _components.end()};
11✔
691
}
11✔
692

693
void SystemImpl::set_system_id(uint8_t system_id)
×
694
{
695
    _target_address.system_id = system_id;
×
696
}
×
697

698
uint8_t SystemImpl::get_own_system_id() const
1,467✔
699
{
700
    return _mavsdk_impl.get_own_system_id();
1,467✔
701
}
702

703
uint8_t SystemImpl::get_own_component_id() const
1,447✔
704
{
705
    return _mavsdk_impl.get_own_component_id();
1,447✔
706
}
707

708
MAV_TYPE SystemImpl::get_vehicle_type() const
×
709
{
710
    return _vehicle_type;
×
711
}
712

713
Vehicle SystemImpl::vehicle() const
×
714
{
715
    return to_vehicle_from_mav_type(_vehicle_type);
×
716
}
717

718
uint8_t SystemImpl::get_own_mav_type() const
×
719
{
720
    return _mavsdk_impl.get_mav_type();
×
721
}
722

723
MavlinkParameterClient::Result SystemImpl::set_param(
×
724
    const std::string& name,
725
    ParamValue value,
726
    std::optional<uint8_t> maybe_component_id,
727
    bool extended)
728
{
729
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
730
        ->set_param(name, value);
×
731
}
732

733
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
734
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
735
{
736
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
737
        ->set_param_float(name, value);
4✔
738
}
739

740
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
741
    const std::string& name,
742
    int32_t value,
743
    std::optional<uint8_t> maybe_component_id,
744
    bool extended)
745
{
746
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
747
        ->set_param_int(name, value);
4✔
748
}
749

750
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
751
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
752
{
753
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
754
        ->set_param_custom(name, value);
4✔
755
}
756

757
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
758
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
759
{
760
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
761
        ->get_all_params();
8✔
762
}
763

764
void SystemImpl::set_param_async(
3✔
765
    const std::string& name,
766
    ParamValue value,
767
    const SetParamCallback& callback,
768
    const void* cookie,
769
    std::optional<uint8_t> maybe_component_id,
770
    bool extended)
771
{
772
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
3✔
773
        ->set_param_async(name, value, callback, cookie);
6✔
774
}
3✔
775

776
void SystemImpl::set_param_float_async(
×
777
    const std::string& name,
778
    float value,
779
    const SetParamCallback& callback,
780
    const void* cookie,
781
    std::optional<uint8_t> maybe_component_id,
782
    bool extended)
783
{
784
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
785
        ->set_param_float_async(name, value, callback, cookie);
×
786
}
×
787

788
void SystemImpl::set_param_int_async(
×
789
    const std::string& name,
790
    int32_t value,
791
    const SetParamCallback& callback,
792
    const void* cookie,
793
    std::optional<uint8_t> maybe_component_id,
794
    bool extended)
795
{
796
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
797
        ->set_param_int_async(name, value, callback, cookie);
×
798
}
×
799

800
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
5✔
801
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
802
{
803
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
804
        ->get_param_float(name);
10✔
805
}
806

807
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
808
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
809
{
810
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
811
        ->get_param_int(name);
10✔
812
}
813

814
std::pair<MavlinkParameterClient::Result, std::string>
815
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
816
{
817
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
818
        ->get_param_custom(name);
8✔
819
}
820

821
void SystemImpl::get_param_async(
×
822
    const std::string& name,
823
    ParamValue value,
824
    const GetParamAnyCallback& callback,
825
    const void* cookie,
826
    std::optional<uint8_t> maybe_component_id,
827
    bool extended)
828
{
829
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
830
        ->get_param_async(name, value, callback, cookie);
×
831
}
×
832

833
void SystemImpl::get_param_float_async(
×
834
    const std::string& name,
835
    const GetParamFloatCallback& callback,
836
    const void* cookie,
837
    std::optional<uint8_t> maybe_component_id,
838
    bool extended)
839
{
840
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
841
        ->get_param_float_async(name, callback, cookie);
×
842
}
×
843

844
void SystemImpl::get_param_int_async(
×
845
    const std::string& name,
846
    const GetParamIntCallback& callback,
847
    const void* cookie,
848
    std::optional<uint8_t> maybe_component_id,
849
    bool extended)
850
{
851
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
852
        ->get_param_int_async(name, callback, cookie);
×
853
}
×
854

855
void SystemImpl::get_param_custom_async(
×
856
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
857
{
858
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
859
}
×
860

861
void SystemImpl::cancel_all_param(const void* cookie)
9✔
862
{
863
    UNUSED(cookie);
9✔
864
    // FIXME: this currently crashes on destruction
865
    // param_sender(1, false)->cancel_all_param(cookie);
866
}
9✔
867

868
MavlinkCommandSender::Result
869
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
870
{
871
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
872
        make_command_flight_mode(system_mode, component_id);
×
873

874
    if (result.first != MavlinkCommandSender::Result::Success) {
×
875
        return result.first;
×
876
    }
877

878
    return send_command(result.second);
×
879
}
880

881
void SystemImpl::set_flight_mode_async(
×
882
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
883
{
884
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
885
        make_command_flight_mode(system_mode, component_id);
×
886

887
    if (result.first != MavlinkCommandSender::Result::Success) {
×
888
        if (callback) {
×
889
            callback(result.first, NAN);
×
890
        }
891
        return;
×
892
    }
893

894
    send_command_async(result.second, callback);
×
895
}
896

897
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
898
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
899
{
900
    if (_autopilot == Autopilot::ArduPilot) {
×
901
        return make_command_ardupilot_mode(flight_mode, component_id);
×
902
    } else {
903
        return make_command_px4_mode(flight_mode, component_id);
×
904
    }
905
}
906

907
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
908
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
909
{
910
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
911
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
912
    const uint8_t mode_type =
×
913
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
914

915
    MavlinkCommandSender::CommandLong command{};
×
916

917
    command.command = MAV_CMD_DO_SET_MODE;
×
918
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
919

920
    switch (_vehicle_type) {
×
921
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
922
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER: {
923
            const auto new_mode = flight_mode_to_ardupilot_rover_mode(flight_mode);
×
924
            if (new_mode == ardupilot::RoverMode::Unknown) {
×
925
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
926
                MavlinkCommandSender::CommandLong empty_command{};
×
927
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
928
            } else {
929
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
930
            }
931
            break;
×
932
        }
933
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
934
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
935
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
936
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
937
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
938
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
939
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
940
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
941
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
942
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
943
                MavlinkCommandSender::CommandLong empty_command{};
×
944
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
945
            } else {
946
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
947
            }
948
            break;
×
949
        }
950

951
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
952
        case MAV_TYPE::MAV_TYPE_COAXIAL:
953
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
954
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
955
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
956
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
957
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
958
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
959
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
960
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
961
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
962
                MavlinkCommandSender::CommandLong empty_command{};
×
963
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
964
            } else {
965
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
966
            }
967
            break;
×
968
        }
969

970
        default:
×
971
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
972
                     << _vehicle_type;
×
973
            MavlinkCommandSender::CommandLong empty_command{};
×
974
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
975
    }
976
    command.target_component_id = component_id;
×
977

978
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
979
}
980
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
981
{
982
    switch (flight_mode) {
×
983
        case FlightMode::Mission:
×
984
            return ardupilot::RoverMode::Auto;
×
985
        case FlightMode::Acro:
×
986
            return ardupilot::RoverMode::Acro;
×
987
        case FlightMode::Hold:
×
988
            return ardupilot::RoverMode::Hold;
×
989
        case FlightMode::ReturnToLaunch:
×
990
            return ardupilot::RoverMode::RTL;
×
991
        case FlightMode::Manual:
×
992
            return ardupilot::RoverMode::Manual;
×
993
        case FlightMode::FollowMe:
×
994
            return ardupilot::RoverMode::Follow;
×
995
        case FlightMode::Offboard:
×
996
            return ardupilot::RoverMode::Guided;
×
997
        case FlightMode::Unknown:
×
998
        case FlightMode::Ready:
999
        case FlightMode::Takeoff:
1000
        case FlightMode::Land:
1001
        case FlightMode::Altctl:
1002
        case FlightMode::Posctl:
1003
        case FlightMode::Rattitude:
1004
        case FlightMode::Stabilized:
1005
        default:
1006
            return ardupilot::RoverMode::Unknown;
×
1007
    }
1008
}
1009
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
1010
{
1011
    switch (flight_mode) {
×
1012
        case FlightMode::Mission:
×
1013
            return ardupilot::CopterMode::Auto;
×
1014
        case FlightMode::Acro:
×
1015
            return ardupilot::CopterMode::Acro;
×
1016
        case FlightMode::Hold:
×
1017
            return ardupilot::CopterMode::Loiter;
×
1018
        case FlightMode::ReturnToLaunch:
×
1019
            return ardupilot::CopterMode::Rtl;
×
1020
        case FlightMode::Land:
×
1021
            return ardupilot::CopterMode::Land;
×
1022
        case FlightMode::Manual:
×
1023
            return ardupilot::CopterMode::Stabilize;
×
1024
        case FlightMode::FollowMe:
×
1025
            return ardupilot::CopterMode::Follow;
×
1026
        case FlightMode::Offboard:
×
1027
            return ardupilot::CopterMode::Guided;
×
1028
        case FlightMode::Altctl:
×
1029
            return ardupilot::CopterMode::AltHold;
×
1030
        case FlightMode::Posctl:
×
1031
            return ardupilot::CopterMode::PosHold;
×
1032
        case FlightMode::Stabilized:
×
1033
            return ardupilot::CopterMode::Stabilize;
×
1034
        case FlightMode::Unknown:
×
1035
        case FlightMode::Ready:
1036
        case FlightMode::Takeoff:
1037
        case FlightMode::Rattitude:
1038
        default:
1039
            return ardupilot::CopterMode::Unknown;
×
1040
    }
1041
}
1042
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
1043
{
1044
    switch (flight_mode) {
×
1045
        case FlightMode::Mission:
×
1046
            return ardupilot::PlaneMode::Auto;
×
1047
        case FlightMode::Acro:
×
1048
            return ardupilot::PlaneMode::Acro;
×
1049
        case FlightMode::Hold:
×
1050
            return ardupilot::PlaneMode::Loiter;
×
1051
        case FlightMode::ReturnToLaunch:
×
1052
            return ardupilot::PlaneMode::Rtl;
×
1053
        case FlightMode::Manual:
×
1054
            return ardupilot::PlaneMode::Manual;
×
1055
        case FlightMode::FBWA:
×
1056
            return ardupilot::PlaneMode::Fbwa;
×
1057
        case FlightMode::Stabilized:
×
1058
            return ardupilot::PlaneMode::Stabilize;
×
1059
        case FlightMode::Offboard:
×
1060
            return ardupilot::PlaneMode::Guided;
×
1061
        case FlightMode::Unknown:
×
1062
            return ardupilot::PlaneMode::Unknown;
×
1063
        default:
×
1064
            return ardupilot::PlaneMode::Unknown;
×
1065
    }
1066
}
1067

1068
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
1069
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
1070
{
1071
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1072
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1073

1074
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1075

1076
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1077
    //       but want to be rather safe than sorry.
1078
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1079
    uint8_t custom_sub_mode = 0;
×
1080

1081
    switch (flight_mode) {
×
1082
        case FlightMode::Hold:
×
1083
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
1084
            break;
×
1085
        case FlightMode::ReturnToLaunch:
×
1086
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
1087
            break;
×
1088
        case FlightMode::Takeoff:
×
1089
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
1090
            break;
×
1091
        case FlightMode::Land:
×
1092
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
1093
            break;
×
1094
        case FlightMode::Mission:
×
1095
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
1096
            break;
×
1097
        case FlightMode::FollowMe:
×
1098
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
1099
            break;
×
1100
        case FlightMode::Offboard:
×
1101
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
1102
            break;
×
1103
        case FlightMode::Manual:
×
1104
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
1105
            break;
×
1106
        case FlightMode::Posctl:
×
1107
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
1108
            break;
×
1109
        case FlightMode::Altctl:
×
1110
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
1111
            break;
×
1112
        case FlightMode::Rattitude:
×
1113
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
1114
            break;
×
1115
        case FlightMode::Acro:
×
1116
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1117
            break;
×
1118
        case FlightMode::Stabilized:
×
1119
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1120
            break;
×
1121
        default:
×
1122
            LogErr() << "Unknown Flight mode.";
×
1123
            MavlinkCommandSender::CommandLong empty_command{};
×
1124
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1125
    }
1126

1127
    MavlinkCommandSender::CommandLong command{};
×
1128

1129
    command.command = MAV_CMD_DO_SET_MODE;
×
1130
    command.params.maybe_param1 = static_cast<float>(mode);
×
1131
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1132
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1133
    command.target_component_id = component_id;
×
1134

1135
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1136
}
1137

1138
FlightMode SystemImpl::get_flight_mode() const
9✔
1139
{
1140
    return _flight_mode;
9✔
1141
}
1142

1143
void SystemImpl::receive_float_param(
×
1144
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1145
{
1146
    if (callback) {
×
1147
        if (result == MavlinkParameterClient::Result::Success) {
×
1148
            callback(result, value.get<float>());
×
1149
        } else {
1150
            callback(result, NAN);
×
1151
        }
1152
    }
1153
}
×
1154

1155
void SystemImpl::receive_int_param(
×
1156
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1157
{
1158
    if (callback) {
×
1159
        if (result == MavlinkParameterClient::Result::Success) {
×
1160
            callback(result, value.get<int32_t>());
×
1161
        } else {
1162
            callback(result, 0);
×
1163
        }
1164
    }
1165
}
×
1166

1167
uint8_t SystemImpl::get_autopilot_id() const
275✔
1168
{
1169
    std::lock_guard<std::mutex> lock(_components_mutex);
275✔
1170
    for (auto compid : _components)
364✔
1171
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
282✔
1172
            return compid;
193✔
1173
        }
1174
    // FIXME: Not sure what should be returned if autopilot is not found
1175
    return uint8_t(0);
82✔
1176
}
275✔
1177

1178
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1179
{
1180
    std::lock_guard<std::mutex> lock(_components_mutex);
×
1181
    std::vector<uint8_t> camera_ids{};
×
1182

1183
    for (auto compid : _components)
×
1184
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1185
            camera_ids.push_back(compid);
×
1186
        }
1187
    return camera_ids;
×
1188
}
×
1189

1190
uint8_t SystemImpl::get_gimbal_id() const
×
1191
{
1192
    std::lock_guard<std::mutex> lock(_components_mutex);
×
1193
    for (auto compid : _components)
×
1194
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1195
            return compid;
×
1196
        }
1197
    return uint8_t(0);
×
1198
}
×
1199

1200
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
5✔
1201
{
1202
    {
1203
        std::lock_guard<std::mutex> lock(_components_mutex);
5✔
1204
        if (_target_address.system_id == 0 && _components.empty()) {
5✔
1205
            return MavlinkCommandSender::Result::NoSystem;
×
1206
        }
1207
    }
5✔
1208
    command.target_system_id = get_system_id();
5✔
1209
    return _command_sender.send_command(command);
5✔
1210
}
1211

1212
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1213
{
1214
    {
1215
        std::lock_guard<std::mutex> lock(_components_mutex);
×
1216
        if (_target_address.system_id == 0 && _components.empty()) {
×
1217
            return MavlinkCommandSender::Result::NoSystem;
×
1218
        }
1219
    }
×
1220
    command.target_system_id = get_system_id();
×
1221
    return _command_sender.send_command(command);
×
1222
}
1223

1224
void SystemImpl::send_command_async(
7✔
1225
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1226
{
1227
    {
1228
        std::lock_guard<std::mutex> lock(_components_mutex);
7✔
1229
        if (_target_address.system_id == 0 && _components.empty()) {
7✔
1230
            if (callback) {
×
1231
                callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1232
            }
1233
            return;
×
1234
        }
1235
    }
7✔
1236
    command.target_system_id = get_system_id();
7✔
1237

1238
    _command_sender.queue_command_async(command, callback);
7✔
1239
}
1240

1241
void SystemImpl::send_command_async(
×
1242
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1243
{
1244
    {
1245
        std::lock_guard<std::mutex> lock(_components_mutex);
×
1246
        if (_target_address.system_id == 0 && _components.empty()) {
×
1247
            if (callback) {
×
1248
                callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1249
            }
1250
            return;
×
1251
        }
1252
    }
×
1253
    command.target_system_id = get_system_id();
×
1254

1255
    _command_sender.queue_command_async(command, callback);
×
1256
}
1257

1258
MavlinkCommandSender::Result
1259
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1260
{
1261
    MavlinkCommandSender::CommandLong command =
1262
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1263
    return send_command(command);
×
1264
}
1265

1266
void SystemImpl::set_msg_rate_async(
1✔
1267
    uint16_t message_id,
1268
    double rate_hz,
1269
    const CommandResultCallback& callback,
1270
    uint8_t component_id)
1271
{
1272
    MavlinkCommandSender::CommandLong command =
1273
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1274
    send_command_async(command, callback);
1✔
1275
}
1✔
1276

1277
MavlinkCommandSender::CommandLong
1278
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1279
{
1280
    MavlinkCommandSender::CommandLong command{};
1✔
1281

1282
    // 0 to request default rate, -1 to stop stream
1283

1284
    float interval_us = 0.0f;
1✔
1285

1286
    if (rate_hz > 0) {
1✔
1287
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1288
    } else if (rate_hz < 0) {
×
1289
        interval_us = -1.0f;
×
1290
    }
1291

1292
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1293
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1294
    command.params.maybe_param2 = interval_us;
1✔
1295
    command.target_component_id = component_id;
1✔
1296

1297
    return command;
1✔
1298
}
1299

1300
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
74✔
1301
{
1302
    assert(plugin_impl);
74✔
1303

1304
    plugin_impl->init();
74✔
1305

1306
    {
1307
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
74✔
1308
        _plugin_impls.push_back(plugin_impl);
74✔
1309
    }
74✔
1310

1311
    // If we're connected already, let's enable it straightaway.
1312
    if (_connected) {
74✔
1313
        plugin_impl->enable();
74✔
1314
    }
1315
}
74✔
1316

1317
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
74✔
1318
{
1319
    assert(plugin_impl);
74✔
1320

1321
    plugin_impl->disable();
74✔
1322
    plugin_impl->deinit();
74✔
1323

1324
    // Remove first, so it won't get enabled/disabled anymore.
1325
    {
1326
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
74✔
1327
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
74✔
1328
        if (found != _plugin_impls.end()) {
74✔
1329
            _plugin_impls.erase(found);
74✔
1330
        }
1331
    }
74✔
1332
}
74✔
1333

1334
void SystemImpl::call_user_callback_located(
998✔
1335
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1336
{
1337
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
998✔
1338
}
998✔
1339

1340
void SystemImpl::param_changed(const std::string& name)
×
1341
{
1342
    for (auto& callback : _param_changed_callbacks) {
×
1343
        callback.second(name);
×
1344
    }
1345
}
×
1346

1347
void SystemImpl::register_param_changed_handler(
×
1348
    const ParamChangedCallback& callback, const void* cookie)
1349
{
1350
    if (!callback) {
×
1351
        LogErr() << "No callback for param_changed_handler supplied.";
×
1352
        return;
×
1353
    }
1354

1355
    if (!cookie) {
×
1356
        LogErr() << "No callback for param_changed_handler supplied.";
×
1357
        return;
×
1358
    }
1359

1360
    _param_changed_callbacks[cookie] = callback;
×
1361
}
1362

1363
void SystemImpl::unregister_param_changed_handler(const void* cookie)
×
1364
{
1365
    auto it = _param_changed_callbacks.find(cookie);
×
1366
    if (it == _param_changed_callbacks.end()) {
×
1367
        LogWarn() << "param_changed_handler for cookie not found";
×
1368
        return;
×
1369
    }
1370
    _param_changed_callbacks.erase(it);
×
1371
}
1372

1373
Time& SystemImpl::get_time()
484✔
1374
{
1375
    return _mavsdk_impl.time;
484✔
1376
}
1377

1378
void SystemImpl::subscribe_param_float(
×
1379
    const std::string& name,
1380
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1381
    const void* cookie)
1382
{
1383
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1384
}
×
1385

1386
void SystemImpl::subscribe_param_int(
×
1387
    const std::string& name,
1388
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1389
    const void* cookie)
1390
{
1391
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1392
}
×
1393
void SystemImpl::subscribe_param_custom(
×
1394
    const std::string& name,
1395
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1396
    const void* cookie)
1397
{
1398
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1399
}
×
1400

1401
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
85✔
1402
{
1403
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
85✔
1404

1405
    for (auto& entry : _mavlink_parameter_clients) {
87✔
1406
        if (entry.component_id == component_id && entry.extended == extended) {
77✔
1407
            return entry.parameter_client.get();
75✔
1408
        }
1409
    }
1410

1411
    _mavlink_parameter_clients.push_back(
10✔
1412
        {std::make_unique<MavlinkParameterClient>(
1413
             _mavsdk_impl.default_server_component_impl().sender(),
10✔
1414
             _mavlink_message_handler,
10✔
1415
             _mavsdk_impl.timeout_handler,
10✔
1416
             [this]() { return timeout_s(); },
84✔
1417
             [this]() { return autopilot(); },
34✔
1418
             get_system_id(),
10✔
1419
             component_id,
1420
             extended),
1421
         component_id,
1422
         extended});
1423

1424
    return _mavlink_parameter_clients.back().parameter_client.get();
10✔
1425
}
85✔
1426

1427
std::vector<Connection*> SystemImpl::get_connections() const
×
1428
{
1429
    return _mavsdk_impl.get_connections();
×
1430
}
1431

1432
mav::MessageSet& SystemImpl::get_message_set() const
22✔
1433
{
1434
    return _mavsdk_impl.get_message_set();
22✔
1435
}
1436

1437
bool SystemImpl::load_custom_xml_to_message_set(const std::string& xml_content)
6✔
1438
{
1439
    return _mavsdk_impl.load_custom_xml_to_message_set(xml_content);
6✔
1440
}
1441

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