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

mavlink / MAVSDK / 14827628259

05 May 2025 02:02AM UTC coverage: 44.06% (-0.2%) from 44.223%
14827628259

push

github

web-flow
Merge pull request #2559 from Luc-Meunier/vehicle-type

core: expose Vehicle type

0 of 120 new or added lines in 3 files covered. (0.0%)

2 existing lines in 2 files now uncovered.

14619 of 33180 relevant lines covered (44.06%)

281.03 hits per line

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

42.15
/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) :
86✔
24
    _mavsdk_impl(mavsdk_impl),
86✔
25
    _command_sender(*this),
86✔
26
    _timesync(*this),
86✔
27
    _ping(*this),
86✔
28
    _mission_transfer_client(
172✔
29
        _mavsdk_impl.default_server_component_impl().sender(),
86✔
30
        _mavlink_message_handler,
86✔
31
        _mavsdk_impl.timeout_handler,
86✔
32
        [this]() { return timeout_s(); },
1✔
33
        [this]() { return autopilot(); }),
1✔
34
    _mavlink_request_message(
86✔
35
        *this, _command_sender, _mavlink_message_handler, _mavsdk_impl.timeout_handler),
86✔
36
    _mavlink_ftp_client(*this),
86✔
37
    _mavlink_component_metadata(*this)
172✔
38
{
39
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
86✔
40
}
86✔
41

42
SystemImpl::~SystemImpl()
86✔
43
{
44
    _should_exit = true;
86✔
45
    _mavlink_message_handler.unregister_all(this);
86✔
46

47
    unregister_timeout_handler(_heartbeat_timeout_cookie);
86✔
48

49
    if (_system_thread != nullptr) {
86✔
50
        _system_thread->join();
86✔
51
        delete _system_thread;
86✔
52
        _system_thread = nullptr;
86✔
53
    }
54
}
86✔
55

56
void SystemImpl::init(uint8_t system_id, uint8_t comp_id)
86✔
57
{
58
    _target_address.system_id = system_id;
86✔
59
    // We use this as a default.
60
    _target_address.component_id = MAV_COMP_ID_AUTOPILOT1;
86✔
61

62
    _mavlink_message_handler.register_one(
86✔
63
        MAVLINK_MSG_ID_HEARTBEAT,
64
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
199✔
65
        this);
66

67
    _mavlink_message_handler.register_one(
86✔
68
        MAVLINK_MSG_ID_STATUSTEXT,
69
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
70
        this);
71

72
    _mavlink_message_handler.register_one(
86✔
73
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
74
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
33✔
75
        this);
76

77
    add_new_component(comp_id);
86✔
78
}
86✔
79

80
bool SystemImpl::is_connected() const
44✔
81
{
82
    return _connected;
44✔
83
}
84

85
void SystemImpl::register_mavlink_message_handler(
358✔
86
    uint16_t msg_id, const MavlinkMessageHandler::Callback& callback, const void* cookie)
87
{
88
    _mavlink_message_handler.register_one(msg_id, callback, cookie);
358✔
89
}
358✔
90

91
void SystemImpl::register_mavlink_message_handler_with_compid(
×
92
    uint16_t msg_id,
93
    uint8_t component_id,
94
    const MavlinkMessageHandler::Callback& callback,
95
    const void* cookie)
96
{
97
    _mavlink_message_handler.register_one_with_component_id(msg_id, component_id, callback, cookie);
×
98
}
×
99

100
void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
101
{
102
    _mavlink_message_handler.unregister_one(msg_id, cookie);
×
103
}
×
104

105
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
356✔
106
{
107
    _mavlink_message_handler.unregister_all(cookie);
356✔
108
}
356✔
109

110
void SystemImpl::update_component_id_messages_handler(
×
111
    uint16_t msg_id, uint8_t component_id, const void* cookie)
112
{
113
    _mavlink_message_handler.update_component_id(msg_id, component_id, cookie);
×
114
}
×
115

116
TimeoutHandler::Cookie
117
SystemImpl::register_timeout_handler(const std::function<void()>& callback, double duration_s)
992✔
118
{
119
    return _mavsdk_impl.timeout_handler.add(callback, duration_s);
992✔
120
}
121

122
void SystemImpl::refresh_timeout_handler(TimeoutHandler::Cookie cookie)
113✔
123
{
124
    _mavsdk_impl.timeout_handler.refresh(cookie);
113✔
125
}
113✔
126

127
void SystemImpl::unregister_timeout_handler(TimeoutHandler::Cookie cookie)
1,028✔
128
{
129
    _mavsdk_impl.timeout_handler.remove(cookie);
1,028✔
130
}
1,028✔
131

132
double SystemImpl::timeout_s() const
978✔
133
{
134
    return _mavsdk_impl.timeout_s();
978✔
135
}
136

137
void SystemImpl::enable_timesync()
×
138
{
139
    _timesync.enable();
×
140
}
×
141

142
System::IsConnectedHandle
143
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
144
{
145
    std::lock_guard<std::mutex> lock(_connection_mutex);
×
146
    return _is_connected_callbacks.subscribe(callback);
×
147
}
×
148

149
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
150
{
151
    _is_connected_callbacks.unsubscribe(handle);
×
152
}
×
153

154
void SystemImpl::process_mavlink_message(mavlink_message_t& message)
1,885✔
155
{
156
    _mavlink_message_handler.process_message(message);
1,885✔
157
}
1,886✔
158

159
CallEveryHandler::Cookie
160
SystemImpl::add_call_every(std::function<void()> callback, float interval_s)
28✔
161
{
162
    return _mavsdk_impl.call_every_handler.add(
56✔
163
        std::move(callback), static_cast<double>(interval_s));
28✔
164
}
165

166
void SystemImpl::change_call_every(float interval_s, CallEveryHandler::Cookie cookie)
×
167
{
168
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
169
}
×
170

171
void SystemImpl::reset_call_every(CallEveryHandler::Cookie cookie)
×
172
{
173
    _mavsdk_impl.call_every_handler.reset(cookie);
×
174
}
×
175

176
void SystemImpl::remove_call_every(CallEveryHandler::Cookie cookie)
28✔
177
{
178
    _mavsdk_impl.call_every_handler.remove(cookie);
28✔
179
}
28✔
180

181
void SystemImpl::register_statustext_handler(
1✔
182
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
183
{
184
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
1✔
185
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
1✔
186
}
1✔
187

188
void SystemImpl::unregister_statustext_handler(void* cookie)
1✔
189
{
190
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
1✔
191
    _statustext_handler_callbacks.erase(std::remove_if(
1✔
192
        _statustext_handler_callbacks.begin(),
193
        _statustext_handler_callbacks.end(),
194
        [&](const auto& entry) { return entry.cookie == cookie; }));
1✔
195
}
1✔
196

197
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
199✔
198
{
199
    mavlink_heartbeat_t heartbeat;
199✔
200
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
199✔
201

202
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
198✔
203
        _autopilot = Autopilot::Px4;
×
204
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
198✔
205
        _autopilot = Autopilot::ArduPilot;
×
206
    }
207

208
    // Only set the vehicle type if the heartbeat is from an autopilot component
209
    // This check only works if the MAV_TYPE::MAV_TYPE_ENUM_END is actually the
210
    // last enumerator.
211
    if (MAV_TYPE::MAV_TYPE_ENUM_END < heartbeat.type) {
199✔
212
        LogErr() << "type received in HEARTBEAT was not recognized";
×
213
    } else {
214
        const auto new_vehicle_type = static_cast<MAV_TYPE>(heartbeat.type);
199✔
215
        if (heartbeat.autopilot != MAV_AUTOPILOT_INVALID && _vehicle_type != new_vehicle_type &&
199✔
216
            new_vehicle_type != MAV_TYPE_GENERIC) {
217
            LogWarn() << "Vehicle type changed (new type: " << static_cast<unsigned>(heartbeat.type)
×
218
                      << ", old type: " << static_cast<unsigned>(_vehicle_type) << ")";
×
219
            _vehicle_type = new_vehicle_type;
×
220
        }
221
    }
222

223
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
199✔
224
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
72✔
225
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
72✔
226
    }
227
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
199✔
228
        _flight_mode =
×
229
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
230
    }
231

232
    set_connected();
199✔
233
}
199✔
234

235
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
236
{
237
    mavlink_statustext_t statustext;
3✔
238
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
239

240
    const auto maybe_result = _statustext_handler.process(statustext);
3✔
241

242
    if (maybe_result.has_value()) {
3✔
243
        LogDebug() << "MAVLink: "
6✔
244
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
245
                   << maybe_result.value().text;
9✔
246

247
        std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
3✔
248
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
249
            entry.callback(maybe_result.value());
3✔
250
        }
251
    }
3✔
252
}
3✔
253

254
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
33✔
255
{
256
    mavlink_autopilot_version_t autopilot_version;
33✔
257
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
33✔
258

259
    _mission_transfer_client.set_int_messages_supported(
33✔
260
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
33✔
261
}
33✔
262

263
void SystemImpl::heartbeats_timed_out()
×
264
{
265
    LogInfo() << "heartbeats timed out";
×
266
    set_disconnected();
×
267
}
×
268

269
void SystemImpl::system_thread()
86✔
270
{
271
    SteadyTimePoint last_ping_time{};
86✔
272

273
    while (!_should_exit) {
9,825✔
274
        {
275
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
9,688✔
276
            for (auto& entry : _mavlink_parameter_clients) {
10,410✔
277
                entry.parameter_client->do_work();
731✔
278
            }
279
        }
9,688✔
280
        _command_sender.do_work();
9,669✔
281
        _timesync.do_work();
9,714✔
282
        _mission_transfer_client.do_work();
9,710✔
283
        _mavlink_ftp_client.do_work();
9,703✔
284

285
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
9,686✔
286
            if (_connected && _autopilot != Autopilot::ArduPilot) {
96✔
287
                _ping.run_once();
10✔
288
            }
289
            last_ping_time = _mavsdk_impl.time.steady_time();
96✔
290
        }
291

292
        if (_connected) {
9,673✔
293
            // Work fairly fast if we're connected.
294
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
9,556✔
295
        } else {
296
            // Be less aggressive when unconnected.
297
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
113✔
298
        }
299
    }
300
}
86✔
301

302
std::string SystemImpl::component_name(uint8_t component_id)
87✔
303
{
304
    switch (component_id) {
87✔
305
        case MAV_COMP_ID_AUTOPILOT1:
33✔
306
            return "Autopilot";
33✔
307
        case MAV_COMP_ID_CAMERA:
9✔
308
            return "Camera 1";
9✔
309
        case MAV_COMP_ID_CAMERA2:
×
310
            return "Camera 2";
×
311
        case MAV_COMP_ID_CAMERA3:
×
312
            return "Camera 3";
×
313
        case MAV_COMP_ID_CAMERA4:
×
314
            return "Camera 4";
×
315
        case MAV_COMP_ID_CAMERA5:
×
316
            return "Camera 5";
×
317
        case MAV_COMP_ID_CAMERA6:
×
318
            return "Camera 6";
×
319
        case MAV_COMP_ID_GIMBAL:
×
320
            return "Gimbal";
×
321
        case MAV_COMP_ID_MISSIONPLANNER:
43✔
322
            return "Ground station";
43✔
323
        case MAV_COMP_ID_ONBOARD_COMPUTER:
1✔
324
            return "Companion Computer";
1✔
325
        case MAV_COMP_ID_WINCH:
×
326
            return "Winch";
×
327
        default:
1✔
328
            return "Unsupported component";
1✔
329
    }
330
}
331

332
ComponentType SystemImpl::component_type(uint8_t component_id)
174✔
333
{
334
    switch (component_id) {
174✔
335
        case MAV_COMP_ID_AUTOPILOT1:
66✔
336
            return ComponentType::Autopilot;
66✔
337
        case MAV_COMP_ID_MISSIONPLANNER:
86✔
338
            return ComponentType::GroundStation;
86✔
339
        case MAV_COMP_ID_ONBOARD_COMPUTER:
2✔
340
        case MAV_COMP_ID_ONBOARD_COMPUTER2:
341
        case MAV_COMP_ID_ONBOARD_COMPUTER3:
342
        case MAV_COMP_ID_ONBOARD_COMPUTER4:
343
            return ComponentType::CompanionComputer;
2✔
344
        case MAV_COMP_ID_CAMERA:
18✔
345
        case MAV_COMP_ID_CAMERA2:
346
        case MAV_COMP_ID_CAMERA3:
347
        case MAV_COMP_ID_CAMERA4:
348
        case MAV_COMP_ID_CAMERA5:
349
        case MAV_COMP_ID_CAMERA6:
350
            return ComponentType::Camera;
18✔
351
        case MAV_COMP_ID_GIMBAL:
×
352
            return ComponentType::Gimbal;
×
353
        case MAV_COMP_ID_ODID_TXRX_1:
×
354
        case MAV_COMP_ID_ODID_TXRX_2:
355
        case MAV_COMP_ID_ODID_TXRX_3:
356
            return ComponentType::RemoteId;
×
357
        default:
2✔
358
            return ComponentType::Custom;
2✔
359
    }
360
}
361

362
void SystemImpl::add_new_component(uint8_t component_id)
1,884✔
363
{
364
    if (component_id == 0) {
1,884✔
365
        return;
×
366
    }
367

368
    auto res_pair = _components.insert(component_id);
1,884✔
369
    if (res_pair.second) {
1,881✔
370
        std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
87✔
371
        _component_discovered_callbacks.queue(
87✔
372
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
373
        _component_discovered_id_callbacks.queue(
87✔
374
            component_type(component_id), component_id, [this](const auto& func) {
×
375
                call_user_callback(func);
×
376
            });
×
377
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
348✔
378
                   << ") added.";
348✔
379
    }
87✔
380
}
381

382
size_t SystemImpl::total_components() const
×
383
{
384
    return _components.size();
×
385
}
386

387
System::ComponentDiscoveredHandle
388
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
389
{
390
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
391
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
392

393
    if (total_components() > 0) {
×
394
        for (const auto& elem : _components) {
×
395
            _component_discovered_callbacks.queue(
×
396
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
397
        }
398
    }
399
    return handle;
×
400
}
×
401

402
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
403
{
404
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
405
    _component_discovered_callbacks.unsubscribe(handle);
×
406
}
×
407

408
System::ComponentDiscoveredIdHandle
409
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
410
{
411
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
412
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
413

414
    if (total_components() > 0) {
×
415
        for (const auto& elem : _components) {
×
416
            _component_discovered_id_callbacks.queue(
×
417
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
418
        }
419
    }
420
    return handle;
×
421
}
×
422

423
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
424
{
425
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
426
    _component_discovered_id_callbacks.unsubscribe(handle);
×
427
}
×
428

429
bool SystemImpl::is_standalone() const
×
430
{
431
    return !has_autopilot();
×
432
}
433

434
bool SystemImpl::has_autopilot() const
152✔
435
{
436
    return get_autopilot_id() != uint8_t(0);
152✔
437
}
438

439
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
440
{
441
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
442
}
443

444
bool SystemImpl::is_camera(uint8_t comp_id)
9✔
445
{
446
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
9✔
447
}
448

449
bool SystemImpl::has_camera(int camera_id) const
9✔
450
{
451
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
9✔
452

453
    if (camera_comp_id == -1) { // Check whether the system has any camera.
9✔
454
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
9✔
455
            return true;
9✔
456
        }
457
    } else { // Look for the camera whose id is `camera_id`.
458
        for (auto compid : _components) {
×
459
            if (compid == camera_comp_id) {
×
460
                return true;
×
461
            }
462
        }
463
    }
464
    return false;
×
465
}
466

467
bool SystemImpl::has_gimbal() const
×
468
{
469
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
470
}
471

472
bool SystemImpl::send_message(mavlink_message_t& message)
×
473
{
474
    return _mavsdk_impl.send_message(message);
×
475
}
476

477
bool SystemImpl::queue_message(
678✔
478
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
479
{
480
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
678✔
481
}
482

483
void SystemImpl::send_autopilot_version_request()
33✔
484
{
485
    mavlink_request_message().request(
33✔
486
        MAVLINK_MSG_ID_AUTOPILOT_VERSION, MAV_COMP_ID_AUTOPILOT1, nullptr);
487
}
33✔
488

489
void SystemImpl::set_connected()
199✔
490
{
491
    bool enable_needed = false;
199✔
492
    {
493
        std::lock_guard<std::mutex> lock(_connection_mutex);
199✔
494

495
        if (!_connected) {
198✔
496
            if (!_components.empty()) {
86✔
497
                LogDebug() << "Discovered " << _components.size() << " component(s)";
86✔
498
            }
499

500
            _connected = true;
86✔
501

502
            // We call this later to avoid deadlocks on creating the server components.
503
            _mavsdk_impl.call_user_callback([this]() {
172✔
504
                // Send a heartbeat back immediately.
505
                _mavsdk_impl.start_sending_heartbeats();
506
            });
507

508
            _heartbeat_timeout_cookie =
86✔
509
                register_timeout_handler([this] { heartbeats_timed_out(); }, HEARTBEAT_TIMEOUT_S);
86✔
510

511
            enable_needed = true;
86✔
512

513
            _is_connected_callbacks.queue(
86✔
514
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
515

516
        } else if (_connected) {
112✔
517
            refresh_timeout_handler(_heartbeat_timeout_cookie);
113✔
518
        }
519
        // If not yet connected there is nothing to do/
520
    }
199✔
521

522
    if (enable_needed) {
199✔
523
        _mavsdk_impl.notify_on_discover();
86✔
524

525
        if (has_autopilot()) {
86✔
526
            send_autopilot_version_request();
33✔
527
        }
528

529
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
86✔
530
        for (auto plugin_impl : _plugin_impls) {
86✔
531
            plugin_impl->enable();
×
532
        }
533
    }
86✔
534
}
199✔
535

536
void SystemImpl::set_disconnected()
×
537
{
538
    {
539
        std::lock_guard<std::mutex> lock(_connection_mutex);
×
540

541
        // This might not be needed because this is probably called from the triggered
542
        // timeout anyway, but it should also do no harm.
543
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
544
        //_heartbeat_timeout_cookie = nullptr;
545

546
        _connected = false;
×
547
        _is_connected_callbacks.queue(
×
548
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
549
    }
×
550
    _mavsdk_impl.notify_on_timeout();
×
551

552
    _mavsdk_impl.stop_sending_heartbeats();
×
553

554
    {
555
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
556
        for (auto plugin_impl : _plugin_impls) {
×
557
            plugin_impl->disable();
×
558
        }
559
    }
×
560
}
×
561

562
uint8_t SystemImpl::get_system_id() const
668✔
563
{
564
    return _target_address.system_id;
668✔
565
}
566

567
std::vector<uint8_t> SystemImpl::component_ids() const
×
568
{
569
    return std::vector<uint8_t>{_components.begin(), _components.end()};
×
570
}
571

572
void SystemImpl::set_system_id(uint8_t system_id)
×
573
{
574
    _target_address.system_id = system_id;
×
575
}
×
576

577
uint8_t SystemImpl::get_own_system_id() const
1,309✔
578
{
579
    return _mavsdk_impl.get_own_system_id();
1,309✔
580
}
581

582
uint8_t SystemImpl::get_own_component_id() const
1,291✔
583
{
584
    return _mavsdk_impl.get_own_component_id();
1,291✔
585
}
586

587
MAV_TYPE SystemImpl::get_vehicle_type() const
×
588
{
589
    return _vehicle_type;
×
590
}
591

NEW
592
Vehicle SystemImpl::vehicle() const
×
593
{
NEW
594
    return to_vehicle_from_mav_type(_vehicle_type);
×
595
}
596

UNCOV
597
uint8_t SystemImpl::get_own_mav_type() const
×
598
{
599
    return _mavsdk_impl.get_mav_type();
×
600
}
601

602
MavlinkParameterClient::Result SystemImpl::set_param(
×
603
    const std::string& name,
604
    ParamValue value,
605
    std::optional<uint8_t> maybe_component_id,
606
    bool extended)
607
{
608
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
609
        ->set_param(name, value);
×
610
}
611

612
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
613
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
614
{
615
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
616
        ->set_param_float(name, value);
4✔
617
}
618

619
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
620
    const std::string& name,
621
    int32_t value,
622
    std::optional<uint8_t> maybe_component_id,
623
    bool extended)
624
{
625
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
626
        ->set_param_int(name, value);
4✔
627
}
628

629
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
630
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
631
{
632
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
633
        ->set_param_custom(name, value);
4✔
634
}
635

636
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
637
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
638
{
639
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
640
        ->get_all_params();
8✔
641
}
642

643
void SystemImpl::set_param_async(
3✔
644
    const std::string& name,
645
    ParamValue value,
646
    const SetParamCallback& callback,
647
    const void* cookie,
648
    std::optional<uint8_t> maybe_component_id,
649
    bool extended)
650
{
651
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
3✔
652
        ->set_param_async(name, value, callback, cookie);
6✔
653
}
3✔
654

655
void SystemImpl::set_param_float_async(
×
656
    const std::string& name,
657
    float value,
658
    const SetParamCallback& callback,
659
    const void* cookie,
660
    std::optional<uint8_t> maybe_component_id,
661
    bool extended)
662
{
663
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
664
        ->set_param_float_async(name, value, callback, cookie);
×
665
}
×
666

667
void SystemImpl::set_param_int_async(
×
668
    const std::string& name,
669
    int32_t value,
670
    const SetParamCallback& callback,
671
    const void* cookie,
672
    std::optional<uint8_t> maybe_component_id,
673
    bool extended)
674
{
675
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
676
        ->set_param_int_async(name, value, callback, cookie);
×
677
}
×
678

679
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
5✔
680
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
681
{
682
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
683
        ->get_param_float(name);
10✔
684
}
685

686
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
687
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
688
{
689
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
690
        ->get_param_int(name);
10✔
691
}
692

693
std::pair<MavlinkParameterClient::Result, std::string>
694
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
695
{
696
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
697
        ->get_param_custom(name);
8✔
698
}
699

700
void SystemImpl::get_param_async(
×
701
    const std::string& name,
702
    ParamValue value,
703
    const GetParamAnyCallback& callback,
704
    const void* cookie,
705
    std::optional<uint8_t> maybe_component_id,
706
    bool extended)
707
{
708
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
709
        ->get_param_async(name, value, callback, cookie);
×
710
}
×
711

712
void SystemImpl::get_param_float_async(
×
713
    const std::string& name,
714
    const GetParamFloatCallback& callback,
715
    const void* cookie,
716
    std::optional<uint8_t> maybe_component_id,
717
    bool extended)
718
{
719
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
720
        ->get_param_float_async(name, callback, cookie);
×
721
}
×
722

723
void SystemImpl::get_param_int_async(
×
724
    const std::string& name,
725
    const GetParamIntCallback& callback,
726
    const void* cookie,
727
    std::optional<uint8_t> maybe_component_id,
728
    bool extended)
729
{
730
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
731
        ->get_param_int_async(name, callback, cookie);
×
732
}
×
733

734
void SystemImpl::get_param_custom_async(
×
735
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
736
{
737
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
738
}
×
739

740
void SystemImpl::cancel_all_param(const void* cookie)
9✔
741
{
742
    UNUSED(cookie);
9✔
743
    // FIXME: this currently crashes on destruction
744
    // param_sender(1, false)->cancel_all_param(cookie);
745
}
9✔
746

747
MavlinkCommandSender::Result
748
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
749
{
750
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
751
        make_command_flight_mode(system_mode, component_id);
×
752

753
    if (result.first != MavlinkCommandSender::Result::Success) {
×
754
        return result.first;
×
755
    }
756

757
    return send_command(result.second);
×
758
}
759

760
void SystemImpl::set_flight_mode_async(
×
761
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
762
{
763
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
764
        make_command_flight_mode(system_mode, component_id);
×
765

766
    if (result.first != MavlinkCommandSender::Result::Success) {
×
767
        if (callback) {
×
768
            callback(result.first, NAN);
×
769
        }
770
        return;
×
771
    }
772

773
    send_command_async(result.second, callback);
×
774
}
775

776
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
777
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
778
{
779
    if (_autopilot == Autopilot::ArduPilot) {
×
780
        return make_command_ardupilot_mode(flight_mode, component_id);
×
781
    } else {
782
        return make_command_px4_mode(flight_mode, component_id);
×
783
    }
784
}
785

786
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
787
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
788
{
789
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
790
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
791
    const uint8_t mode_type =
×
792
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
793

794
    MavlinkCommandSender::CommandLong command{};
×
795

796
    command.command = MAV_CMD_DO_SET_MODE;
×
797
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
798

799
    switch (_vehicle_type) {
×
800
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
801
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER: {
802
            const auto new_mode = flight_mode_to_ardupilot_rover_mode(flight_mode);
×
803
            if (new_mode == ardupilot::RoverMode::Unknown) {
×
804
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
805
                MavlinkCommandSender::CommandLong empty_command{};
×
806
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
807
            } else {
808
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
809
            }
810
            break;
×
811
        }
812
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
813
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
814
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
815
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
816
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
817
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
818
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
819
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
820
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
821
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
822
                MavlinkCommandSender::CommandLong empty_command{};
×
823
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
824
            } else {
825
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
826
            }
827
            break;
×
828
        }
829

830
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
831
        case MAV_TYPE::MAV_TYPE_COAXIAL:
832
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
833
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
834
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
835
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
836
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
837
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
838
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
839
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
840
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
841
                MavlinkCommandSender::CommandLong empty_command{};
×
842
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
843
            } else {
844
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
845
            }
846
            break;
×
847
        }
848

849
        default:
×
850
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
851
                     << _vehicle_type;
×
852
            MavlinkCommandSender::CommandLong empty_command{};
×
853
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
854
    }
855
    command.target_component_id = component_id;
×
856

857
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
858
}
859
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
860
{
861
    switch (flight_mode) {
×
862
        case FlightMode::Mission:
×
863
            return ardupilot::RoverMode::Auto;
×
864
        case FlightMode::Acro:
×
865
            return ardupilot::RoverMode::Acro;
×
866
        case FlightMode::Hold:
×
867
            return ardupilot::RoverMode::Hold;
×
868
        case FlightMode::ReturnToLaunch:
×
869
            return ardupilot::RoverMode::RTL;
×
870
        case FlightMode::Manual:
×
871
            return ardupilot::RoverMode::Manual;
×
872
        case FlightMode::FollowMe:
×
873
            return ardupilot::RoverMode::Follow;
×
874
        case FlightMode::Offboard:
×
875
            return ardupilot::RoverMode::Guided;
×
876
        case FlightMode::Unknown:
×
877
        case FlightMode::Ready:
878
        case FlightMode::Takeoff:
879
        case FlightMode::Land:
880
        case FlightMode::Altctl:
881
        case FlightMode::Posctl:
882
        case FlightMode::Rattitude:
883
        case FlightMode::Stabilized:
884
        default:
885
            return ardupilot::RoverMode::Unknown;
×
886
    }
887
}
888
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
889
{
890
    switch (flight_mode) {
×
891
        case FlightMode::Mission:
×
892
            return ardupilot::CopterMode::Auto;
×
893
        case FlightMode::Acro:
×
894
            return ardupilot::CopterMode::Acro;
×
895
        case FlightMode::Hold:
×
896
            return ardupilot::CopterMode::Loiter;
×
897
        case FlightMode::ReturnToLaunch:
×
898
            return ardupilot::CopterMode::Rtl;
×
899
        case FlightMode::Land:
×
900
            return ardupilot::CopterMode::Land;
×
901
        case FlightMode::Manual:
×
902
            return ardupilot::CopterMode::Stabilize;
×
903
        case FlightMode::FollowMe:
×
904
            return ardupilot::CopterMode::Follow;
×
905
        case FlightMode::Offboard:
×
906
            return ardupilot::CopterMode::Guided;
×
907
        case FlightMode::Altctl:
×
908
            return ardupilot::CopterMode::AltHold;
×
909
        case FlightMode::Posctl:
×
910
            return ardupilot::CopterMode::PosHold;
×
911
        case FlightMode::Stabilized:
×
912
            return ardupilot::CopterMode::Stabilize;
×
913
        case FlightMode::Unknown:
×
914
        case FlightMode::Ready:
915
        case FlightMode::Takeoff:
916
        case FlightMode::Rattitude:
917
        default:
918
            return ardupilot::CopterMode::Unknown;
×
919
    }
920
}
921
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
922
{
923
    switch (flight_mode) {
×
924
        case FlightMode::Mission:
×
925
            return ardupilot::PlaneMode::Auto;
×
926
        case FlightMode::Acro:
×
927
            return ardupilot::PlaneMode::Acro;
×
928
        case FlightMode::Hold:
×
929
            return ardupilot::PlaneMode::Loiter;
×
930
        case FlightMode::ReturnToLaunch:
×
931
            return ardupilot::PlaneMode::Rtl;
×
932
        case FlightMode::Manual:
×
933
            return ardupilot::PlaneMode::Manual;
×
934
        case FlightMode::FBWA:
×
935
            return ardupilot::PlaneMode::Fbwa;
×
936
        case FlightMode::Stabilized:
×
937
            return ardupilot::PlaneMode::Stabilize;
×
938
        case FlightMode::Offboard:
×
939
            return ardupilot::PlaneMode::Guided;
×
940
        case FlightMode::Unknown:
×
941
            return ardupilot::PlaneMode::Unknown;
×
942
        default:
×
943
            return ardupilot::PlaneMode::Unknown;
×
944
    }
945
}
946

947
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
948
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
949
{
950
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
951
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
952

953
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
954

955
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
956
    //       but want to be rather safe than sorry.
957
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
958
    uint8_t custom_sub_mode = 0;
×
959

960
    switch (flight_mode) {
×
961
        case FlightMode::Hold:
×
962
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
963
            break;
×
964
        case FlightMode::ReturnToLaunch:
×
965
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
966
            break;
×
967
        case FlightMode::Takeoff:
×
968
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
969
            break;
×
970
        case FlightMode::Land:
×
971
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
972
            break;
×
973
        case FlightMode::Mission:
×
974
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
975
            break;
×
976
        case FlightMode::FollowMe:
×
977
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
978
            break;
×
979
        case FlightMode::Offboard:
×
980
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
981
            break;
×
982
        case FlightMode::Manual:
×
983
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
984
            break;
×
985
        case FlightMode::Posctl:
×
986
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
987
            break;
×
988
        case FlightMode::Altctl:
×
989
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
990
            break;
×
991
        case FlightMode::Rattitude:
×
992
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
993
            break;
×
994
        case FlightMode::Acro:
×
995
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
996
            break;
×
997
        case FlightMode::Stabilized:
×
998
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
999
            break;
×
1000
        default:
×
1001
            LogErr() << "Unknown Flight mode.";
×
1002
            MavlinkCommandSender::CommandLong empty_command{};
×
1003
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1004
    }
1005

1006
    MavlinkCommandSender::CommandLong command{};
×
1007

1008
    command.command = MAV_CMD_DO_SET_MODE;
×
1009
    command.params.maybe_param1 = static_cast<float>(mode);
×
1010
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1011
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1012
    command.target_component_id = component_id;
×
1013

1014
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1015
}
1016

1017
FlightMode SystemImpl::get_flight_mode() const
7✔
1018
{
1019
    return _flight_mode;
7✔
1020
}
1021

1022
void SystemImpl::receive_float_param(
×
1023
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1024
{
1025
    if (callback) {
×
1026
        if (result == MavlinkParameterClient::Result::Success) {
×
1027
            callback(result, value.get<float>());
×
1028
        } else {
1029
            callback(result, NAN);
×
1030
        }
1031
    }
1032
}
×
1033

1034
void SystemImpl::receive_int_param(
×
1035
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1036
{
1037
    if (callback) {
×
1038
        if (result == MavlinkParameterClient::Result::Success) {
×
1039
            callback(result, value.get<int32_t>());
×
1040
        } else {
1041
            callback(result, 0);
×
1042
        }
1043
    }
1044
}
×
1045

1046
uint8_t SystemImpl::get_autopilot_id() const
197✔
1047
{
1048
    for (auto compid : _components)
257✔
1049
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
200✔
1050
            return compid;
140✔
1051
        }
1052
    // FIXME: Not sure what should be returned if autopilot is not found
1053
    return uint8_t(0);
57✔
1054
}
1055

1056
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1057
{
1058
    std::vector<uint8_t> camera_ids{};
×
1059

1060
    for (auto compid : _components)
×
1061
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1062
            camera_ids.push_back(compid);
×
1063
        }
1064
    return camera_ids;
×
1065
}
1066

1067
uint8_t SystemImpl::get_gimbal_id() const
×
1068
{
1069
    for (auto compid : _components)
×
1070
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1071
            return compid;
×
1072
        }
1073
    return uint8_t(0);
×
1074
}
1075

1076
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
5✔
1077
{
1078
    if (_target_address.system_id == 0 && _components.empty()) {
5✔
1079
        return MavlinkCommandSender::Result::NoSystem;
×
1080
    }
1081
    command.target_system_id = get_system_id();
5✔
1082
    return _command_sender.send_command(command);
5✔
1083
}
1084

1085
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1086
{
1087
    if (_target_address.system_id == 0 && _components.empty()) {
×
1088
        return MavlinkCommandSender::Result::NoSystem;
×
1089
    }
1090
    command.target_system_id = get_system_id();
×
1091
    return _command_sender.send_command(command);
×
1092
}
1093

1094
void SystemImpl::send_command_async(
7✔
1095
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1096
{
1097
    if (_target_address.system_id == 0 && _components.empty()) {
7✔
1098
        if (callback) {
×
1099
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1100
        }
1101
        return;
×
1102
    }
1103
    command.target_system_id = get_system_id();
7✔
1104

1105
    _command_sender.queue_command_async(command, callback);
7✔
1106
}
1107

1108
void SystemImpl::send_command_async(
×
1109
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1110
{
1111
    if (_target_address.system_id == 0 && _components.empty()) {
×
1112
        if (callback) {
×
1113
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1114
        }
1115
        return;
×
1116
    }
1117
    command.target_system_id = get_system_id();
×
1118

1119
    _command_sender.queue_command_async(command, callback);
×
1120
}
1121

1122
MavlinkCommandSender::Result
1123
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1124
{
1125
    MavlinkCommandSender::CommandLong command =
×
1126
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1127
    return send_command(command);
×
1128
}
1129

1130
void SystemImpl::set_msg_rate_async(
1✔
1131
    uint16_t message_id,
1132
    double rate_hz,
1133
    const CommandResultCallback& callback,
1134
    uint8_t component_id)
1135
{
1136
    MavlinkCommandSender::CommandLong command =
1✔
1137
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1138
    send_command_async(command, callback);
1✔
1139
}
1✔
1140

1141
MavlinkCommandSender::CommandLong
1142
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1143
{
1144
    MavlinkCommandSender::CommandLong command{};
1✔
1145

1146
    // 0 to request default rate, -1 to stop stream
1147

1148
    float interval_us = 0.0f;
1✔
1149

1150
    if (rate_hz > 0) {
1✔
1151
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1152
    } else if (rate_hz < 0) {
×
1153
        interval_us = -1.0f;
×
1154
    }
1155

1156
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1157
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1158
    command.params.maybe_param2 = interval_us;
1✔
1159
    command.target_component_id = component_id;
1✔
1160

1161
    return command;
1✔
1162
}
1163

1164
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
45✔
1165
{
1166
    assert(plugin_impl);
45✔
1167

1168
    plugin_impl->init();
45✔
1169

1170
    {
1171
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
45✔
1172
        _plugin_impls.push_back(plugin_impl);
45✔
1173
    }
45✔
1174

1175
    // If we're connected already, let's enable it straightaway.
1176
    if (_connected) {
45✔
1177
        plugin_impl->enable();
45✔
1178
    }
1179
}
45✔
1180

1181
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
45✔
1182
{
1183
    assert(plugin_impl);
45✔
1184

1185
    plugin_impl->disable();
45✔
1186
    plugin_impl->deinit();
45✔
1187

1188
    // Remove first, so it won't get enabled/disabled anymore.
1189
    {
1190
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
45✔
1191
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
45✔
1192
        if (found != _plugin_impls.end()) {
45✔
1193
            _plugin_impls.erase(found);
45✔
1194
        }
1195
    }
45✔
1196
}
45✔
1197

1198
void SystemImpl::call_user_callback_located(
810✔
1199
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1200
{
1201
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
810✔
1202
}
810✔
1203

1204
void SystemImpl::param_changed(const std::string& name)
×
1205
{
1206
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1207

1208
    for (auto& callback : _param_changed_callbacks) {
×
1209
        callback.second(name);
×
1210
    }
1211
}
×
1212

1213
void SystemImpl::register_param_changed_handler(
×
1214
    const ParamChangedCallback& callback, const void* cookie)
1215
{
1216
    if (!callback) {
×
1217
        LogErr() << "No callback for param_changed_handler supplied.";
×
1218
        return;
×
1219
    }
1220

1221
    if (!cookie) {
×
1222
        LogErr() << "No callback for param_changed_handler supplied.";
×
1223
        return;
×
1224
    }
1225

1226
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1227

1228
    _param_changed_callbacks[cookie] = callback;
×
1229
}
×
1230

1231
void SystemImpl::unregister_param_changed_handler(const void* cookie)
×
1232
{
1233
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1234

1235
    auto it = _param_changed_callbacks.find(cookie);
×
1236
    if (it == _param_changed_callbacks.end()) {
×
1237
        LogWarn() << "param_changed_handler for cookie not found";
×
1238
        return;
×
1239
    }
1240
    _param_changed_callbacks.erase(it);
×
1241
}
×
1242

1243
Time& SystemImpl::get_time()
229✔
1244
{
1245
    return _mavsdk_impl.time;
229✔
1246
}
1247

1248
void SystemImpl::subscribe_param_float(
×
1249
    const std::string& name,
1250
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1251
    const void* cookie)
1252
{
1253
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1254
}
×
1255

1256
void SystemImpl::subscribe_param_int(
×
1257
    const std::string& name,
1258
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1259
    const void* cookie)
1260
{
1261
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1262
}
×
1263
void SystemImpl::subscribe_param_custom(
×
1264
    const std::string& name,
1265
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1266
    const void* cookie)
1267
{
1268
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1269
}
×
1270

1271
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
79✔
1272
{
1273
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
79✔
1274

1275
    for (auto& entry : _mavlink_parameter_clients) {
81✔
1276
        if (entry.component_id == component_id && entry.extended == extended) {
71✔
1277
            return entry.parameter_client.get();
69✔
1278
        }
1279
    }
1280

1281
    _mavlink_parameter_clients.push_back(
30✔
1282
        {std::make_unique<MavlinkParameterClient>(
1283
             _mavsdk_impl.default_server_component_impl().sender(),
10✔
1284
             _mavlink_message_handler,
10✔
1285
             _mavsdk_impl.timeout_handler,
10✔
1286
             [this]() { return timeout_s(); },
73✔
1287
             [this]() { return autopilot(); },
32✔
1288
             get_system_id(),
20✔
1289
             component_id,
1290
             extended),
1291
         component_id,
1292
         extended});
1293

1294
    return _mavlink_parameter_clients.back().parameter_client.get();
10✔
1295
}
79✔
1296

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