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

mavlink / MAVSDK / 16247112396

13 Jul 2025 08:18AM UTC coverage: 46.221% (+1.0%) from 45.212%
16247112396

Pull #2610

github

web-flow
Merge a15009557 into 6c112e71f
Pull Request #2610: Integrate parts of libmav into MAVSDK and add MavlinkDirect plugin

727 of 980 new or added lines in 15 files covered. (74.18%)

27 existing lines in 5 files now uncovered.

16217 of 35086 relevant lines covered (46.22%)

148063.0 hits per line

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

43.61
/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 "server_component_impl.h"
6
#include "plugin_impl_base.h"
7
#include "px4_custom_mode.h"
8
#include "ardupilot_custom_mode.h"
9
#include "callback_list.tpp"
10
#include "unused.h"
11
#include <cassert>
12
#include <cstdlib>
13
#include <functional>
14
#include <future>
15
#include <utility>
16

17
namespace mavsdk {
18

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

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

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

48
SystemImpl::~SystemImpl()
98✔
49
{
50
    _should_exit = true;
98✔
51
    _mavlink_message_handler.unregister_all(this);
98✔
52
    unregister_all_libmav_message_handlers(this);
98✔
53

54
    unregister_timeout_handler(_heartbeat_timeout_cookie);
98✔
55

56
    if (_system_thread != nullptr) {
98✔
57
        _system_thread->join();
98✔
58
        delete _system_thread;
98✔
59
        _system_thread = nullptr;
98✔
60
    }
61
}
98✔
62

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

69
    _mavlink_message_handler.register_one(
98✔
70
        MAVLINK_MSG_ID_HEARTBEAT,
71
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
191✔
72
        this);
73

74
    _mavlink_message_handler.register_one(
98✔
75
        MAVLINK_MSG_ID_STATUSTEXT,
76
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
77
        this);
78

79
    _mavlink_message_handler.register_one(
98✔
80
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
81
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
39✔
82
        this);
83

84
    add_new_component(comp_id);
98✔
85
}
98✔
86

87
bool SystemImpl::is_connected() const
48✔
88
{
89
    return _connected;
48✔
90
}
91

92
void SystemImpl::register_mavlink_message_handler(
418✔
93
    uint16_t msg_id, const MavlinkMessageHandler::Callback& callback, const void* cookie)
94
{
95
    _mavlink_message_handler.register_one(msg_id, callback, cookie);
418✔
96
}
417✔
97

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

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

112
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
405✔
113
{
114
    _mavlink_message_handler.unregister_all(cookie);
405✔
115
}
405✔
116

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

123
void SystemImpl::process_libmav_message(const LibmavMessage& message)
2,075✔
124
{
125
    // Call all registered libmav message handlers
126
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
2,075✔
127

128
    if (_message_debugging) {
2,077✔
NEW
129
        LogDebug() << "SystemImpl::process_libmav_message: " << message.message_name
×
NEW
130
                   << ", registered handlers: " << _libmav_message_handlers.size();
×
131
    }
132

133
    for (const auto& handler : _libmav_message_handlers) {
2,094✔
134
        if (_message_debugging) {
17✔
NEW
135
            LogDebug() << "Checking handler for message: '" << handler.message_name << "' against '"
×
NEW
136
                       << message.message_name << "'";
×
137
        }
138
        // Check if message name matches (empty string means match all messages)
139
        if (!handler.message_name.empty() && handler.message_name != message.message_name) {
17✔
140
            if (_message_debugging) {
10✔
NEW
141
                LogDebug() << "Handler message name mismatch, skipping";
×
142
            }
143
            continue;
10✔
144
        }
145

146
        // Check if component ID matches (if specified)
147
        if (handler.component_id.has_value() &&
7✔
NEW
148
            handler.component_id.value() != message.component_id) {
×
NEW
149
            continue;
×
150
        }
151

152
        // Call the handler
153
        if (_message_debugging) {
7✔
NEW
154
            LogDebug() << "Calling libmav handler for: " << message.message_name;
×
155
        }
156
        if (handler.callback) {
7✔
157
            handler.callback(message);
7✔
158
        } else {
NEW
159
            LogWarn() << "Handler callback is null!";
×
160
        }
161
    }
162
}
2,076✔
163

164
void SystemImpl::register_libmav_message_handler(
5✔
165
    const std::string& message_name, const LibmavMessageCallback& callback, const void* cookie)
166
{
167
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
5✔
168
    if (_message_debugging) {
5✔
NEW
169
        LogDebug() << "Registering libmav handler for message: '" << message_name
×
NEW
170
                   << "', total handlers will be: " << (_libmav_message_handlers.size() + 1);
×
171
    }
172
    _libmav_message_handlers.push_back({message_name, callback, cookie, std::nullopt});
5✔
173
}
5✔
174

NEW
175
void SystemImpl::register_libmav_message_handler_with_compid(
×
176
    const std::string& message_name,
177
    uint8_t cmp_id,
178
    const LibmavMessageCallback& callback,
179
    const void* cookie)
180
{
NEW
181
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
×
NEW
182
    _libmav_message_handlers.push_back({message_name, callback, cookie, cmp_id});
×
NEW
183
}
×
184

NEW
185
void SystemImpl::unregister_libmav_message_handler(
×
186
    const std::string& message_name, const void* cookie)
187
{
NEW
188
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
×
189

NEW
190
    _libmav_message_handlers.erase(
×
NEW
191
        std::remove_if(
×
192
            _libmav_message_handlers.begin(),
193
            _libmav_message_handlers.end(),
NEW
194
            [&](const LibmavMessageHandler& handler) {
×
NEW
195
                return handler.message_name == message_name && handler.cookie == cookie;
×
196
            }),
NEW
197
        _libmav_message_handlers.end());
×
NEW
198
}
×
199

200
void SystemImpl::unregister_all_libmav_message_handlers(const void* cookie)
98✔
201
{
202
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
98✔
203

204
    _libmav_message_handlers.erase(
392✔
205
        std::remove_if(
196✔
206
            _libmav_message_handlers.begin(),
207
            _libmav_message_handlers.end(),
208
            [&](const LibmavMessageHandler& handler) { return handler.cookie == cookie; }),
5✔
209
        _libmav_message_handlers.end());
196✔
210
}
98✔
211

212
TimeoutHandler::Cookie
213
SystemImpl::register_timeout_handler(const std::function<void()>& callback, double duration_s)
1,096✔
214
{
215
    return _mavsdk_impl.timeout_handler.add(callback, duration_s);
1,096✔
216
}
217

218
void SystemImpl::refresh_timeout_handler(TimeoutHandler::Cookie cookie)
95✔
219
{
220
    _mavsdk_impl.timeout_handler.refresh(cookie);
95✔
221
}
96✔
222

223
void SystemImpl::unregister_timeout_handler(TimeoutHandler::Cookie cookie)
1,228✔
224
{
225
    _mavsdk_impl.timeout_handler.remove(cookie);
1,228✔
226
}
1,228✔
227

228
double SystemImpl::timeout_s() const
1,074✔
229
{
230
    return _mavsdk_impl.timeout_s();
1,074✔
231
}
232

233
void SystemImpl::enable_timesync()
×
234
{
235
    _timesync.enable();
×
236
}
×
237

238
System::IsConnectedHandle
239
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
240
{
241
    return _is_connected_callbacks.subscribe(callback);
×
242
}
243

244
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
245
{
246
    _is_connected_callbacks.unsubscribe(handle);
×
247
}
×
248

249
void SystemImpl::process_mavlink_message(mavlink_message_t& message)
2,063✔
250
{
251
    _mavlink_message_handler.process_message(message);
2,063✔
252
}
2,065✔
253

254
CallEveryHandler::Cookie
255
SystemImpl::add_call_every(std::function<void()> callback, float interval_s)
29✔
256
{
257
    return _mavsdk_impl.call_every_handler.add(
58✔
258
        std::move(callback), static_cast<double>(interval_s));
29✔
259
}
260

261
void SystemImpl::change_call_every(float interval_s, CallEveryHandler::Cookie cookie)
×
262
{
263
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
264
}
×
265

266
void SystemImpl::reset_call_every(CallEveryHandler::Cookie cookie)
×
267
{
268
    _mavsdk_impl.call_every_handler.reset(cookie);
×
269
}
×
270

271
void SystemImpl::remove_call_every(CallEveryHandler::Cookie cookie)
29✔
272
{
273
    _mavsdk_impl.call_every_handler.remove(cookie);
29✔
274
}
29✔
275

276
void SystemImpl::register_statustext_handler(
2✔
277
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
278
{
279
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
280
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
2✔
281
}
2✔
282

283
void SystemImpl::unregister_statustext_handler(void* cookie)
2✔
284
{
285
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
286
    _statustext_handler_callbacks.erase(std::remove_if(
2✔
287
        _statustext_handler_callbacks.begin(),
288
        _statustext_handler_callbacks.end(),
289
        [&](const auto& entry) { return entry.cookie == cookie; }));
2✔
290
}
2✔
291

292
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
194✔
293
{
294
    mavlink_heartbeat_t heartbeat;
194✔
295
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
194✔
296

297
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
193✔
298
        _autopilot = Autopilot::Px4;
×
299
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
193✔
300
        _autopilot = Autopilot::ArduPilot;
×
301
    }
302

303
    // Only set the vehicle type if the heartbeat is from an autopilot component
304
    // This check only works if the MAV_TYPE::MAV_TYPE_ENUM_END is actually the
305
    // last enumerator.
306
    if (MAV_TYPE::MAV_TYPE_ENUM_END < heartbeat.type) {
194✔
307
        LogErr() << "type received in HEARTBEAT was not recognized";
×
308
    } else {
309
        const auto new_vehicle_type = static_cast<MAV_TYPE>(heartbeat.type);
194✔
310
        if (heartbeat.autopilot != MAV_AUTOPILOT_INVALID && _vehicle_type != new_vehicle_type &&
194✔
311
            new_vehicle_type != MAV_TYPE_GENERIC) {
312
            LogWarn() << "Vehicle type changed (new type: " << static_cast<unsigned>(heartbeat.type)
×
313
                      << ", old type: " << static_cast<unsigned>(_vehicle_type) << ")";
×
314
            _vehicle_type = new_vehicle_type;
×
315
        }
316
    }
317

318
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
194✔
319
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
78✔
320
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
78✔
321
    }
322
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
194✔
323
        _flight_mode =
×
324
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
325
    }
326

327
    set_connected();
194✔
328
}
194✔
329

330
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
331
{
332
    mavlink_statustext_t statustext;
3✔
333
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
334

335
    const auto maybe_result = _statustext_handler.process(statustext);
3✔
336

337
    if (maybe_result.has_value()) {
3✔
338
        LogDebug() << "MAVLink: "
6✔
339
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
340
                   << maybe_result.value().text;
9✔
341

342
        std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
3✔
343
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
344
            entry.callback(maybe_result.value());
3✔
345
        }
346
    }
3✔
347
}
3✔
348

349
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
39✔
350
{
351
    mavlink_autopilot_version_t autopilot_version;
39✔
352
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
39✔
353

354
    _mission_transfer_client.set_int_messages_supported(
39✔
355
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
39✔
356
}
39✔
357

358
void SystemImpl::heartbeats_timed_out()
×
359
{
360
    LogInfo() << "heartbeats timed out";
×
361
    set_disconnected();
×
362
}
×
363

364
void SystemImpl::system_thread()
98✔
365
{
366
    SteadyTimePoint last_ping_time{};
98✔
367

368
    while (!_should_exit) {
9,410✔
369
        {
370
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
9,311✔
371
            for (auto& entry : _mavlink_parameter_clients) {
10,250✔
372
                entry.parameter_client->do_work();
940✔
373
            }
374
        }
9,302✔
375
        _command_sender.do_work();
9,296✔
376
        _timesync.do_work();
9,303✔
377
        _mission_transfer_client.do_work();
9,303✔
378
        _mavlink_ftp_client.do_work();
9,290✔
379

380
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
9,284✔
381
            if (_connected && _autopilot != Autopilot::ArduPilot) {
100✔
382
                _ping.run_once();
2✔
383
            }
384
            last_ping_time = _mavsdk_impl.time.steady_time();
100✔
385
        }
386

387
        if (_connected) {
9,307✔
388
            // Work fairly fast if we're connected.
389
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
9,191✔
390
        } else {
391
            // Be less aggressive when unconnected.
392
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
100✔
393
        }
394
    }
395
}
98✔
396

397
std::string SystemImpl::component_name(uint8_t component_id)
99✔
398
{
399
    switch (component_id) {
99✔
400
        case MAV_COMP_ID_AUTOPILOT1:
39✔
401
            return "Autopilot";
39✔
402
        case MAV_COMP_ID_CAMERA:
9✔
403
            return "Camera 1";
9✔
404
        case MAV_COMP_ID_CAMERA2:
×
405
            return "Camera 2";
×
406
        case MAV_COMP_ID_CAMERA3:
×
407
            return "Camera 3";
×
408
        case MAV_COMP_ID_CAMERA4:
×
409
            return "Camera 4";
×
410
        case MAV_COMP_ID_CAMERA5:
×
411
            return "Camera 5";
×
412
        case MAV_COMP_ID_CAMERA6:
×
413
            return "Camera 6";
×
414
        case MAV_COMP_ID_GIMBAL:
×
415
            return "Gimbal";
×
416
        case MAV_COMP_ID_MISSIONPLANNER:
49✔
417
            return "Ground station";
49✔
418
        case MAV_COMP_ID_ONBOARD_COMPUTER:
1✔
419
            return "Companion Computer";
1✔
420
        case MAV_COMP_ID_WINCH:
×
421
            return "Winch";
×
422
        default:
1✔
423
            return "Unsupported component";
1✔
424
    }
425
}
426

427
ComponentType SystemImpl::component_type(uint8_t component_id)
198✔
428
{
429
    switch (component_id) {
198✔
430
        case MAV_COMP_ID_AUTOPILOT1:
78✔
431
            return ComponentType::Autopilot;
78✔
432
        case MAV_COMP_ID_MISSIONPLANNER:
98✔
433
            return ComponentType::GroundStation;
98✔
434
        case MAV_COMP_ID_ONBOARD_COMPUTER:
2✔
435
        case MAV_COMP_ID_ONBOARD_COMPUTER2:
436
        case MAV_COMP_ID_ONBOARD_COMPUTER3:
437
        case MAV_COMP_ID_ONBOARD_COMPUTER4:
438
            return ComponentType::CompanionComputer;
2✔
439
        case MAV_COMP_ID_CAMERA:
18✔
440
        case MAV_COMP_ID_CAMERA2:
441
        case MAV_COMP_ID_CAMERA3:
442
        case MAV_COMP_ID_CAMERA4:
443
        case MAV_COMP_ID_CAMERA5:
444
        case MAV_COMP_ID_CAMERA6:
445
            return ComponentType::Camera;
18✔
446
        case MAV_COMP_ID_GIMBAL:
×
447
            return ComponentType::Gimbal;
×
448
        case MAV_COMP_ID_ODID_TXRX_1:
×
449
        case MAV_COMP_ID_ODID_TXRX_2:
450
        case MAV_COMP_ID_ODID_TXRX_3:
451
            return ComponentType::RemoteId;
×
452
        default:
2✔
453
            return ComponentType::Custom;
2✔
454
    }
455
}
456

457
void SystemImpl::add_new_component(uint8_t component_id)
4,141✔
458
{
459
    if (component_id == 0) {
4,141✔
460
        return;
×
461
    }
462

463
    auto res_pair = _components.insert(component_id);
4,141✔
464
    if (res_pair.second) {
4,141✔
465
        std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
99✔
466
        _component_discovered_callbacks.queue(
99✔
467
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
468
        _component_discovered_id_callbacks.queue(
99✔
469
            component_type(component_id), component_id, [this](const auto& func) {
×
470
                call_user_callback(func);
×
471
            });
×
472
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
396✔
473
                   << ") added.";
396✔
474
    }
99✔
475
}
476

477
size_t SystemImpl::total_components() const
×
478
{
479
    return _components.size();
×
480
}
481

482
System::ComponentDiscoveredHandle
483
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
484
{
485
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
486
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
487

488
    if (total_components() > 0) {
×
489
        for (const auto& elem : _components) {
×
490
            _component_discovered_callbacks.queue(
×
491
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
492
        }
493
    }
494
    return handle;
×
495
}
×
496

497
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
498
{
499
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
500
    _component_discovered_callbacks.unsubscribe(handle);
×
501
}
×
502

503
System::ComponentDiscoveredIdHandle
504
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
505
{
506
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
507
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
508

509
    if (total_components() > 0) {
×
510
        for (const auto& elem : _components) {
×
511
            _component_discovered_id_callbacks.queue(
×
512
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
513
        }
514
    }
515
    return handle;
×
516
}
×
517

518
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
519
{
520
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
521
    _component_discovered_id_callbacks.unsubscribe(handle);
×
522
}
×
523

524
bool SystemImpl::is_standalone() const
×
525
{
526
    return !has_autopilot();
×
527
}
528

529
bool SystemImpl::has_autopilot() const
176✔
530
{
531
    return get_autopilot_id() != uint8_t(0);
176✔
532
}
533

534
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
535
{
536
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
537
}
538

539
bool SystemImpl::is_camera(uint8_t comp_id)
9✔
540
{
541
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
9✔
542
}
543

544
bool SystemImpl::has_camera(int camera_id) const
9✔
545
{
546
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
9✔
547

548
    if (camera_comp_id == -1) { // Check whether the system has any camera.
9✔
549
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
9✔
550
            return true;
9✔
551
        }
552
    } else { // Look for the camera whose id is `camera_id`.
553
        for (auto compid : _components) {
×
554
            if (compid == camera_comp_id) {
×
555
                return true;
×
556
            }
557
        }
558
    }
559
    return false;
×
560
}
561

562
bool SystemImpl::has_gimbal() const
×
563
{
564
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
565
}
566

567
bool SystemImpl::send_message(mavlink_message_t& message)
×
568
{
569
    return _mavsdk_impl.send_message(message);
×
570
}
571

572
bool SystemImpl::queue_message(
760✔
573
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
574
{
575
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
760✔
576
}
577

578
void SystemImpl::send_autopilot_version_request()
39✔
579
{
580
    mavlink_request_message().request(
39✔
581
        MAVLINK_MSG_ID_AUTOPILOT_VERSION, MAV_COMP_ID_AUTOPILOT1, nullptr);
582
}
39✔
583

584
void SystemImpl::set_connected()
191✔
585
{
586
    bool enable_needed = false;
191✔
587
    {
588
        if (!_connected) {
191✔
589
            if (!_components.empty()) {
98✔
590
                LogDebug() << "Discovered " << _components.size() << " component(s)";
98✔
591
            }
592

593
            _connected = true;
98✔
594

595
            // Only send heartbeats if we're not shutting down
596
            if (!_should_exit) {
98✔
597
                // We call this later to avoid deadlocks on creating the server components.
598
                _mavsdk_impl.call_user_callback([this]() {
196✔
599
                    // Send a heartbeat back immediately.
600
                    _mavsdk_impl.start_sending_heartbeats();
601
                });
602
            }
603

604
            _heartbeat_timeout_cookie =
98✔
605
                register_timeout_handler([this] { heartbeats_timed_out(); }, HEARTBEAT_TIMEOUT_S);
98✔
606

607
            enable_needed = true;
98✔
608

609
            // Queue callbacks without holding any locks to avoid deadlocks
610
            _is_connected_callbacks.queue(
98✔
611
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
612

613
        } else if (_connected) {
92✔
614
            refresh_timeout_handler(_heartbeat_timeout_cookie);
92✔
615
        }
616
        // If not yet connected there is nothing to do
617
    }
618

619
    if (enable_needed) {
194✔
620
        // Notify about the new system without holding any locks
621
        _mavsdk_impl.notify_on_discover();
98✔
622

623
        if (has_autopilot()) {
98✔
624
            send_autopilot_version_request();
39✔
625
        }
626

627
        // Enable plugins
628
        std::vector<PluginImplBase*> plugin_impls_to_enable;
98✔
629
        {
630
            std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
98✔
631
            plugin_impls_to_enable = _plugin_impls;
98✔
632
        }
98✔
633

634
        for (auto plugin_impl : plugin_impls_to_enable) {
98✔
635
            plugin_impl->enable();
×
636
        }
637
    }
98✔
638
}
194✔
639

640
void SystemImpl::set_disconnected()
×
641
{
642
    {
643
        // This might not be needed because this is probably called from the triggered
644
        // timeout anyway, but it should also do no harm.
645
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
646
        //_heartbeat_timeout_cookie = nullptr;
647

648
        _connected = false;
×
649
        _is_connected_callbacks.queue(
×
650
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
651
    }
652
    _mavsdk_impl.notify_on_timeout();
×
653

654
    _mavsdk_impl.stop_sending_heartbeats();
×
655

656
    {
657
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
658
        for (auto plugin_impl : _plugin_impls) {
×
659
            plugin_impl->disable();
×
660
        }
661
    }
×
662
}
×
663

664
uint8_t SystemImpl::get_system_id() const
759✔
665
{
666
    return _target_address.system_id;
759✔
667
}
668

669
std::vector<uint8_t> SystemImpl::component_ids() const
6✔
670
{
671
    return std::vector<uint8_t>{_components.begin(), _components.end()};
6✔
672
}
673

674
void SystemImpl::set_system_id(uint8_t system_id)
×
675
{
676
    _target_address.system_id = system_id;
×
677
}
×
678

679
uint8_t SystemImpl::get_own_system_id() const
1,392✔
680
{
681
    return _mavsdk_impl.get_own_system_id();
1,392✔
682
}
683

684
uint8_t SystemImpl::get_own_component_id() const
1,374✔
685
{
686
    return _mavsdk_impl.get_own_component_id();
1,374✔
687
}
688

689
MAV_TYPE SystemImpl::get_vehicle_type() const
×
690
{
691
    return _vehicle_type;
×
692
}
693

694
Vehicle SystemImpl::vehicle() const
×
695
{
696
    return to_vehicle_from_mav_type(_vehicle_type);
×
697
}
698

699
uint8_t SystemImpl::get_own_mav_type() const
×
700
{
701
    return _mavsdk_impl.get_mav_type();
×
702
}
703

704
MavlinkParameterClient::Result SystemImpl::set_param(
×
705
    const std::string& name,
706
    ParamValue value,
707
    std::optional<uint8_t> maybe_component_id,
708
    bool extended)
709
{
710
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
711
        ->set_param(name, value);
×
712
}
713

714
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
715
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
716
{
717
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
718
        ->set_param_float(name, value);
4✔
719
}
720

721
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
722
    const std::string& name,
723
    int32_t value,
724
    std::optional<uint8_t> maybe_component_id,
725
    bool extended)
726
{
727
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
728
        ->set_param_int(name, value);
4✔
729
}
730

731
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
732
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
733
{
734
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
735
        ->set_param_custom(name, value);
4✔
736
}
737

738
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
739
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
740
{
741
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
742
        ->get_all_params();
8✔
743
}
744

745
void SystemImpl::set_param_async(
3✔
746
    const std::string& name,
747
    ParamValue value,
748
    const SetParamCallback& callback,
749
    const void* cookie,
750
    std::optional<uint8_t> maybe_component_id,
751
    bool extended)
752
{
753
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
3✔
754
        ->set_param_async(name, value, callback, cookie);
6✔
755
}
3✔
756

757
void SystemImpl::set_param_float_async(
×
758
    const std::string& name,
759
    float value,
760
    const SetParamCallback& callback,
761
    const void* cookie,
762
    std::optional<uint8_t> maybe_component_id,
763
    bool extended)
764
{
765
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
766
        ->set_param_float_async(name, value, callback, cookie);
×
767
}
×
768

769
void SystemImpl::set_param_int_async(
×
770
    const std::string& name,
771
    int32_t value,
772
    const SetParamCallback& callback,
773
    const void* cookie,
774
    std::optional<uint8_t> maybe_component_id,
775
    bool extended)
776
{
777
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
778
        ->set_param_int_async(name, value, callback, cookie);
×
779
}
×
780

781
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
5✔
782
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
783
{
784
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
785
        ->get_param_float(name);
10✔
786
}
787

788
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
789
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
790
{
791
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
792
        ->get_param_int(name);
10✔
793
}
794

795
std::pair<MavlinkParameterClient::Result, std::string>
796
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
797
{
798
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
799
        ->get_param_custom(name);
8✔
800
}
801

802
void SystemImpl::get_param_async(
×
803
    const std::string& name,
804
    ParamValue value,
805
    const GetParamAnyCallback& callback,
806
    const void* cookie,
807
    std::optional<uint8_t> maybe_component_id,
808
    bool extended)
809
{
810
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
811
        ->get_param_async(name, value, callback, cookie);
×
812
}
×
813

814
void SystemImpl::get_param_float_async(
×
815
    const std::string& name,
816
    const GetParamFloatCallback& callback,
817
    const void* cookie,
818
    std::optional<uint8_t> maybe_component_id,
819
    bool extended)
820
{
821
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
822
        ->get_param_float_async(name, callback, cookie);
×
823
}
×
824

825
void SystemImpl::get_param_int_async(
×
826
    const std::string& name,
827
    const GetParamIntCallback& callback,
828
    const void* cookie,
829
    std::optional<uint8_t> maybe_component_id,
830
    bool extended)
831
{
832
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
833
        ->get_param_int_async(name, callback, cookie);
×
834
}
×
835

836
void SystemImpl::get_param_custom_async(
×
837
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
838
{
839
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
840
}
×
841

842
void SystemImpl::cancel_all_param(const void* cookie)
9✔
843
{
844
    UNUSED(cookie);
9✔
845
    // FIXME: this currently crashes on destruction
846
    // param_sender(1, false)->cancel_all_param(cookie);
847
}
9✔
848

849
MavlinkCommandSender::Result
850
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
851
{
852
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
853
        make_command_flight_mode(system_mode, component_id);
×
854

855
    if (result.first != MavlinkCommandSender::Result::Success) {
×
856
        return result.first;
×
857
    }
858

859
    return send_command(result.second);
×
860
}
861

862
void SystemImpl::set_flight_mode_async(
×
863
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
864
{
865
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
866
        make_command_flight_mode(system_mode, component_id);
×
867

868
    if (result.first != MavlinkCommandSender::Result::Success) {
×
869
        if (callback) {
×
870
            callback(result.first, NAN);
×
871
        }
872
        return;
×
873
    }
874

875
    send_command_async(result.second, callback);
×
876
}
877

878
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
879
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
880
{
881
    if (_autopilot == Autopilot::ArduPilot) {
×
882
        return make_command_ardupilot_mode(flight_mode, component_id);
×
883
    } else {
884
        return make_command_px4_mode(flight_mode, component_id);
×
885
    }
886
}
887

888
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
889
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
890
{
891
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
892
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
893
    const uint8_t mode_type =
×
894
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
895

896
    MavlinkCommandSender::CommandLong command{};
×
897

898
    command.command = MAV_CMD_DO_SET_MODE;
×
899
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
900

901
    switch (_vehicle_type) {
×
902
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
903
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER: {
904
            const auto new_mode = flight_mode_to_ardupilot_rover_mode(flight_mode);
×
905
            if (new_mode == ardupilot::RoverMode::Unknown) {
×
906
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
907
                MavlinkCommandSender::CommandLong empty_command{};
×
908
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
909
            } else {
910
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
911
            }
912
            break;
×
913
        }
914
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
915
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
916
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
917
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
918
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
919
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
920
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
921
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
922
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
923
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
924
                MavlinkCommandSender::CommandLong empty_command{};
×
925
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
926
            } else {
927
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
928
            }
929
            break;
×
930
        }
931

932
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
933
        case MAV_TYPE::MAV_TYPE_COAXIAL:
934
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
935
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
936
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
937
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
938
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
939
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
940
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
941
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
942
                LogErr() << "Cannot translate flight mode to ArduPilot Copter 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
        default:
×
952
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
953
                     << _vehicle_type;
×
954
            MavlinkCommandSender::CommandLong empty_command{};
×
955
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
956
    }
957
    command.target_component_id = component_id;
×
958

959
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
960
}
961
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
962
{
963
    switch (flight_mode) {
×
964
        case FlightMode::Mission:
×
965
            return ardupilot::RoverMode::Auto;
×
966
        case FlightMode::Acro:
×
967
            return ardupilot::RoverMode::Acro;
×
968
        case FlightMode::Hold:
×
969
            return ardupilot::RoverMode::Hold;
×
970
        case FlightMode::ReturnToLaunch:
×
971
            return ardupilot::RoverMode::RTL;
×
972
        case FlightMode::Manual:
×
973
            return ardupilot::RoverMode::Manual;
×
974
        case FlightMode::FollowMe:
×
975
            return ardupilot::RoverMode::Follow;
×
976
        case FlightMode::Offboard:
×
977
            return ardupilot::RoverMode::Guided;
×
978
        case FlightMode::Unknown:
×
979
        case FlightMode::Ready:
980
        case FlightMode::Takeoff:
981
        case FlightMode::Land:
982
        case FlightMode::Altctl:
983
        case FlightMode::Posctl:
984
        case FlightMode::Rattitude:
985
        case FlightMode::Stabilized:
986
        default:
987
            return ardupilot::RoverMode::Unknown;
×
988
    }
989
}
990
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
991
{
992
    switch (flight_mode) {
×
993
        case FlightMode::Mission:
×
994
            return ardupilot::CopterMode::Auto;
×
995
        case FlightMode::Acro:
×
996
            return ardupilot::CopterMode::Acro;
×
997
        case FlightMode::Hold:
×
998
            return ardupilot::CopterMode::Loiter;
×
999
        case FlightMode::ReturnToLaunch:
×
1000
            return ardupilot::CopterMode::Rtl;
×
1001
        case FlightMode::Land:
×
1002
            return ardupilot::CopterMode::Land;
×
1003
        case FlightMode::Manual:
×
1004
            return ardupilot::CopterMode::Stabilize;
×
1005
        case FlightMode::FollowMe:
×
1006
            return ardupilot::CopterMode::Follow;
×
1007
        case FlightMode::Offboard:
×
1008
            return ardupilot::CopterMode::Guided;
×
1009
        case FlightMode::Altctl:
×
1010
            return ardupilot::CopterMode::AltHold;
×
1011
        case FlightMode::Posctl:
×
1012
            return ardupilot::CopterMode::PosHold;
×
1013
        case FlightMode::Stabilized:
×
1014
            return ardupilot::CopterMode::Stabilize;
×
1015
        case FlightMode::Unknown:
×
1016
        case FlightMode::Ready:
1017
        case FlightMode::Takeoff:
1018
        case FlightMode::Rattitude:
1019
        default:
1020
            return ardupilot::CopterMode::Unknown;
×
1021
    }
1022
}
1023
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
1024
{
1025
    switch (flight_mode) {
×
1026
        case FlightMode::Mission:
×
1027
            return ardupilot::PlaneMode::Auto;
×
1028
        case FlightMode::Acro:
×
1029
            return ardupilot::PlaneMode::Acro;
×
1030
        case FlightMode::Hold:
×
1031
            return ardupilot::PlaneMode::Loiter;
×
1032
        case FlightMode::ReturnToLaunch:
×
1033
            return ardupilot::PlaneMode::Rtl;
×
1034
        case FlightMode::Manual:
×
1035
            return ardupilot::PlaneMode::Manual;
×
1036
        case FlightMode::FBWA:
×
1037
            return ardupilot::PlaneMode::Fbwa;
×
1038
        case FlightMode::Stabilized:
×
1039
            return ardupilot::PlaneMode::Stabilize;
×
1040
        case FlightMode::Offboard:
×
1041
            return ardupilot::PlaneMode::Guided;
×
1042
        case FlightMode::Unknown:
×
1043
            return ardupilot::PlaneMode::Unknown;
×
1044
        default:
×
1045
            return ardupilot::PlaneMode::Unknown;
×
1046
    }
1047
}
1048

1049
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
1050
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
1051
{
1052
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1053
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1054

1055
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1056

1057
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1058
    //       but want to be rather safe than sorry.
1059
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1060
    uint8_t custom_sub_mode = 0;
×
1061

1062
    switch (flight_mode) {
×
1063
        case FlightMode::Hold:
×
1064
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
1065
            break;
×
1066
        case FlightMode::ReturnToLaunch:
×
1067
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
1068
            break;
×
1069
        case FlightMode::Takeoff:
×
1070
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
1071
            break;
×
1072
        case FlightMode::Land:
×
1073
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
1074
            break;
×
1075
        case FlightMode::Mission:
×
1076
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
1077
            break;
×
1078
        case FlightMode::FollowMe:
×
1079
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
1080
            break;
×
1081
        case FlightMode::Offboard:
×
1082
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
1083
            break;
×
1084
        case FlightMode::Manual:
×
1085
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
1086
            break;
×
1087
        case FlightMode::Posctl:
×
1088
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
1089
            break;
×
1090
        case FlightMode::Altctl:
×
1091
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
1092
            break;
×
1093
        case FlightMode::Rattitude:
×
1094
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
1095
            break;
×
1096
        case FlightMode::Acro:
×
1097
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1098
            break;
×
1099
        case FlightMode::Stabilized:
×
1100
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1101
            break;
×
1102
        default:
×
1103
            LogErr() << "Unknown Flight mode.";
×
1104
            MavlinkCommandSender::CommandLong empty_command{};
×
1105
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1106
    }
1107

1108
    MavlinkCommandSender::CommandLong command{};
×
1109

1110
    command.command = MAV_CMD_DO_SET_MODE;
×
1111
    command.params.maybe_param1 = static_cast<float>(mode);
×
1112
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1113
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1114
    command.target_component_id = component_id;
×
1115

1116
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1117
}
1118

1119
FlightMode SystemImpl::get_flight_mode() const
8✔
1120
{
1121
    return _flight_mode;
8✔
1122
}
1123

1124
void SystemImpl::receive_float_param(
×
1125
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1126
{
1127
    if (callback) {
×
1128
        if (result == MavlinkParameterClient::Result::Success) {
×
1129
            callback(result, value.get<float>());
×
1130
        } else {
1131
            callback(result, NAN);
×
1132
        }
1133
    }
1134
}
×
1135

1136
void SystemImpl::receive_int_param(
×
1137
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1138
{
1139
    if (callback) {
×
1140
        if (result == MavlinkParameterClient::Result::Success) {
×
1141
            callback(result, value.get<int32_t>());
×
1142
        } else {
1143
            callback(result, 0);
×
1144
        }
1145
    }
1146
}
×
1147

1148
uint8_t SystemImpl::get_autopilot_id() const
221✔
1149
{
1150
    for (auto compid : _components)
287✔
1151
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
224✔
1152
            return compid;
158✔
1153
        }
1154
    // FIXME: Not sure what should be returned if autopilot is not found
1155
    return uint8_t(0);
63✔
1156
}
1157

1158
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1159
{
1160
    std::vector<uint8_t> camera_ids{};
×
1161

1162
    for (auto compid : _components)
×
1163
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1164
            camera_ids.push_back(compid);
×
1165
        }
1166
    return camera_ids;
×
1167
}
1168

1169
uint8_t SystemImpl::get_gimbal_id() const
×
1170
{
1171
    for (auto compid : _components)
×
1172
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1173
            return compid;
×
1174
        }
1175
    return uint8_t(0);
×
1176
}
1177

1178
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
5✔
1179
{
1180
    if (_target_address.system_id == 0 && _components.empty()) {
5✔
1181
        return MavlinkCommandSender::Result::NoSystem;
×
1182
    }
1183
    command.target_system_id = get_system_id();
5✔
1184
    return _command_sender.send_command(command);
5✔
1185
}
1186

1187
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1188
{
1189
    if (_target_address.system_id == 0 && _components.empty()) {
×
1190
        return MavlinkCommandSender::Result::NoSystem;
×
1191
    }
1192
    command.target_system_id = get_system_id();
×
1193
    return _command_sender.send_command(command);
×
1194
}
1195

1196
void SystemImpl::send_command_async(
7✔
1197
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1198
{
1199
    if (_target_address.system_id == 0 && _components.empty()) {
7✔
1200
        if (callback) {
×
1201
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1202
        }
1203
        return;
×
1204
    }
1205
    command.target_system_id = get_system_id();
7✔
1206

1207
    _command_sender.queue_command_async(command, callback);
7✔
1208
}
1209

1210
void SystemImpl::send_command_async(
×
1211
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1212
{
1213
    if (_target_address.system_id == 0 && _components.empty()) {
×
1214
        if (callback) {
×
1215
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1216
        }
1217
        return;
×
1218
    }
1219
    command.target_system_id = get_system_id();
×
1220

1221
    _command_sender.queue_command_async(command, callback);
×
1222
}
1223

1224
MavlinkCommandSender::Result
1225
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1226
{
1227
    MavlinkCommandSender::CommandLong command =
×
1228
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1229
    return send_command(command);
×
1230
}
1231

1232
void SystemImpl::set_msg_rate_async(
1✔
1233
    uint16_t message_id,
1234
    double rate_hz,
1235
    const CommandResultCallback& callback,
1236
    uint8_t component_id)
1237
{
1238
    MavlinkCommandSender::CommandLong command =
1✔
1239
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1240
    send_command_async(command, callback);
1✔
1241
}
1✔
1242

1243
MavlinkCommandSender::CommandLong
1244
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1245
{
1246
    MavlinkCommandSender::CommandLong command{};
1✔
1247

1248
    // 0 to request default rate, -1 to stop stream
1249

1250
    float interval_us = 0.0f;
1✔
1251

1252
    if (rate_hz > 0) {
1✔
1253
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1254
    } else if (rate_hz < 0) {
×
1255
        interval_us = -1.0f;
×
1256
    }
1257

1258
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1259
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1260
    command.params.maybe_param2 = interval_us;
1✔
1261
    command.target_component_id = component_id;
1✔
1262

1263
    return command;
1✔
1264
}
1265

1266
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
56✔
1267
{
1268
    assert(plugin_impl);
56✔
1269

1270
    plugin_impl->init();
56✔
1271

1272
    {
1273
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
56✔
1274
        _plugin_impls.push_back(plugin_impl);
56✔
1275
    }
56✔
1276

1277
    // If we're connected already, let's enable it straightaway.
1278
    if (_connected) {
56✔
1279
        plugin_impl->enable();
56✔
1280
    }
1281
}
56✔
1282

1283
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
56✔
1284
{
1285
    assert(plugin_impl);
56✔
1286

1287
    plugin_impl->disable();
56✔
1288
    plugin_impl->deinit();
56✔
1289

1290
    // Remove first, so it won't get enabled/disabled anymore.
1291
    {
1292
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
56✔
1293
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
56✔
1294
        if (found != _plugin_impls.end()) {
56✔
1295
            _plugin_impls.erase(found);
56✔
1296
        }
1297
    }
56✔
1298
}
56✔
1299

1300
void SystemImpl::call_user_callback_located(
897✔
1301
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1302
{
1303
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
897✔
1304
}
897✔
1305

1306
void SystemImpl::param_changed(const std::string& name)
×
1307
{
1308
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1309

1310
    for (auto& callback : _param_changed_callbacks) {
×
1311
        callback.second(name);
×
1312
    }
1313
}
×
1314

1315
void SystemImpl::register_param_changed_handler(
×
1316
    const ParamChangedCallback& callback, const void* cookie)
1317
{
1318
    if (!callback) {
×
1319
        LogErr() << "No callback for param_changed_handler supplied.";
×
1320
        return;
×
1321
    }
1322

1323
    if (!cookie) {
×
1324
        LogErr() << "No callback for param_changed_handler supplied.";
×
1325
        return;
×
1326
    }
1327

1328
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1329

1330
    _param_changed_callbacks[cookie] = callback;
×
1331
}
×
1332

1333
void SystemImpl::unregister_param_changed_handler(const void* cookie)
×
1334
{
1335
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1336

1337
    auto it = _param_changed_callbacks.find(cookie);
×
1338
    if (it == _param_changed_callbacks.end()) {
×
1339
        LogWarn() << "param_changed_handler for cookie not found";
×
1340
        return;
×
1341
    }
1342
    _param_changed_callbacks.erase(it);
×
1343
}
×
1344

1345
Time& SystemImpl::get_time()
399✔
1346
{
1347
    return _mavsdk_impl.time;
399✔
1348
}
1349

1350
void SystemImpl::subscribe_param_float(
×
1351
    const std::string& name,
1352
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1353
    const void* cookie)
1354
{
1355
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1356
}
×
1357

1358
void SystemImpl::subscribe_param_int(
×
1359
    const std::string& name,
1360
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1361
    const void* cookie)
1362
{
1363
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1364
}
×
1365
void SystemImpl::subscribe_param_custom(
×
1366
    const std::string& name,
1367
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1368
    const void* cookie)
1369
{
1370
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1371
}
×
1372

1373
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
85✔
1374
{
1375
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
85✔
1376

1377
    for (auto& entry : _mavlink_parameter_clients) {
87✔
1378
        if (entry.component_id == component_id && entry.extended == extended) {
77✔
1379
            return entry.parameter_client.get();
75✔
1380
        }
1381
    }
1382

1383
    _mavlink_parameter_clients.push_back(
30✔
1384
        {std::make_unique<MavlinkParameterClient>(
1385
             _mavsdk_impl.default_server_component_impl().sender(),
10✔
1386
             _mavlink_message_handler,
10✔
1387
             _mavsdk_impl.timeout_handler,
10✔
1388
             [this]() { return timeout_s(); },
79✔
1389
             [this]() { return autopilot(); },
34✔
1390
             get_system_id(),
20✔
1391
             component_id,
1392
             extended),
1393
         component_id,
1394
         extended});
1395

1396
    return _mavlink_parameter_clients.back().parameter_client.get();
10✔
1397
}
85✔
1398

1399
std::vector<Connection*> SystemImpl::get_connections() const
9✔
1400
{
1401
    return _mavsdk_impl.get_connections();
9✔
1402
}
1403

1404
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc