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

mavlink / MAVSDK / 9106360009

16 May 2024 04:12AM UTC coverage: 36.895% (+0.04%) from 36.858%
9106360009

push

github

web-flow
Merge pull request #2301 from mavlink/pr-timeout-fixes

TimeoutHandler fixes

40 of 47 new or added lines in 4 files covered. (85.11%)

3 existing lines in 2 files now uncovered.

10890 of 29516 relevant lines covered (36.9%)

118.96 hits per line

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

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

18
namespace mavsdk {
19

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

24
SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) :
69✔
25
    _mavsdk_impl(mavsdk_impl),
26
    _command_sender(*this),
27
    _timesync(*this),
28
    _ping(*this),
29
    _mission_transfer_client(
30
        _mavsdk_impl.default_server_component_impl().sender(),
69✔
31
        _mavlink_message_handler,
69✔
32
        _mavsdk_impl.timeout_handler,
69✔
33
        [this]() { return timeout_s(); },
1✔
34
        [this]() { return autopilot(); }),
1✔
35
    _request_message(
36
        *this, _command_sender, _mavlink_message_handler, _mavsdk_impl.timeout_handler),
69✔
37
    _mavlink_ftp_client(*this)
138✔
38
{
39
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
69✔
40
}
69✔
41

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

47
    unregister_timeout_handler(_heartbeat_timeout_cookie);
69✔
48

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

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

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

67
    _mavlink_message_handler.register_one(
69✔
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(
69✔
73
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
74
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
38✔
75
        this);
76

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

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

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

91
void SystemImpl::register_mavlink_message_handler_with_compid(
7✔
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);
7✔
98
}
7✔
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)
280✔
106
{
107
    _mavlink_message_handler.unregister_all(cookie);
280✔
108
}
280✔
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
void SystemImpl::register_timeout_handler(
893✔
117
    const std::function<void()>& callback, double duration_s, void** cookie)
118
{
119
    _mavsdk_impl.timeout_handler.add(callback, duration_s, cookie);
893✔
120
}
893✔
121

122
void SystemImpl::refresh_timeout_handler(const void* cookie)
10✔
123
{
124
    _mavsdk_impl.timeout_handler.refresh(cookie);
10✔
125
}
10✔
126

127
void SystemImpl::unregister_timeout_handler(const void* cookie)
926✔
128
{
129
    _mavsdk_impl.timeout_handler.remove(cookie);
926✔
130
}
926✔
131

132
double SystemImpl::timeout_s() const
866✔
133
{
134
    return _mavsdk_impl.timeout_s();
866✔
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,451✔
155
{
156
    _mavlink_message_handler.process_message(message);
1,451✔
157
}
1,451✔
158

159
void SystemImpl::add_call_every(std::function<void()> callback, float interval_s, void** cookie)
4✔
160
{
161
    _mavsdk_impl.call_every_handler.add(
8✔
162
        std::move(callback), static_cast<double>(interval_s), cookie);
4✔
163
}
4✔
164

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

170
void SystemImpl::reset_call_every(const void* cookie)
×
171
{
172
    _mavsdk_impl.call_every_handler.reset(cookie);
×
173
}
×
174

175
void SystemImpl::remove_call_every(const void* cookie)
9✔
176
{
177
    _mavsdk_impl.call_every_handler.remove(cookie);
9✔
178
}
9✔
179

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

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

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

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

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

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

231
    set_connected();
79✔
232
}
79✔
233

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

239
    const auto maybe_result = _statustext_handler.process(statustext);
6✔
240

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

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

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

258
    _mission_transfer_client.set_int_messages_supported(
38✔
259
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
38✔
260
}
38✔
261

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

268
void SystemImpl::system_thread()
69✔
269
{
270
    SteadyTimePoint last_ping_time{};
69✔
271

272
    while (!_should_exit) {
3,078✔
273
        {
274
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
6,018✔
275
            for (auto& entry : _mavlink_parameter_clients) {
3,391✔
276
                entry.parameter_client->do_work();
382✔
277
            }
278
        }
279
        _command_sender.do_work();
3,009✔
280
        _timesync.do_work();
3,009✔
281
        _mission_transfer_client.do_work();
3,009✔
282
        _mavlink_ftp_client.do_work();
3,009✔
283

284
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
3,009✔
285
            if (_connected && _autopilot != Autopilot::ArduPilot) {
69✔
286
                _ping.run_once();
×
287
            }
288
            last_ping_time = _mavsdk_impl.time.steady_time();
69✔
289
        }
290

291
        if (_connected) {
3,009✔
292
            // Work fairly fast if we're connected.
293
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
2,921✔
294
        } else {
295
            // Be less aggressive when unconnected.
296
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
88✔
297
        }
298
    }
299
}
69✔
300

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

331
System::ComponentType SystemImpl::component_type(uint8_t component_id)
140✔
332
{
333
    switch (component_id) {
140✔
334
        case MAV_COMP_ID_AUTOPILOT1:
66✔
335
            return System::ComponentType::AUTOPILOT;
66✔
336
        case MAV_COMP_ID_CAMERA:
2✔
337
        case MAV_COMP_ID_CAMERA2:
338
        case MAV_COMP_ID_CAMERA3:
339
        case MAV_COMP_ID_CAMERA4:
340
        case MAV_COMP_ID_CAMERA5:
341
        case MAV_COMP_ID_CAMERA6:
342
            return System::ComponentType::CAMERA;
2✔
343
        case MAV_COMP_ID_GIMBAL:
×
344
            return System::ComponentType::GIMBAL;
×
345
        default:
72✔
346
            return System::ComponentType::UNKNOWN;
72✔
347
    }
348
}
349

350
void SystemImpl::add_new_component(uint8_t component_id)
1,451✔
351
{
352
    if (component_id == 0) {
1,451✔
353
        return;
×
354
    }
355

356
    auto res_pair = _components.insert(component_id);
1,451✔
357
    if (res_pair.second) {
1,451✔
358
        std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
140✔
359
        _component_discovered_callbacks.queue(
70✔
360
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
361
        _component_discovered_id_callbacks.queue(
70✔
362
            component_type(component_id), component_id, [this](const auto& func) {
×
363
                call_user_callback(func);
×
364
            });
×
365
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
280✔
366
                   << ") added.";
280✔
367
    }
368
}
369

370
size_t SystemImpl::total_components() const
×
371
{
372
    return _components.size();
×
373
}
374

375
System::ComponentDiscoveredHandle
376
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
377
{
378
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
379
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
380

381
    if (total_components() > 0) {
×
382
        for (const auto& elem : _components) {
×
383
            _component_discovered_callbacks.queue(
×
384
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
385
        }
386
    }
387
    return handle;
×
388
}
389

390
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
391
{
392
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
393
    _component_discovered_callbacks.unsubscribe(handle);
×
394
}
×
395

396
System::ComponentDiscoveredIdHandle
397
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
398
{
399
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
400
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
401

402
    if (total_components() > 0) {
×
403
        for (const auto& elem : _components) {
×
404
            _component_discovered_id_callbacks.queue(
×
405
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
406
        }
407
    }
408
    return handle;
×
409
}
410

411
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
412
{
413
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
414
    _component_discovered_id_callbacks.unsubscribe(handle);
×
415
}
×
416

417
bool SystemImpl::is_standalone() const
×
418
{
419
    return !has_autopilot();
×
420
}
421

422
bool SystemImpl::has_autopilot() const
136✔
423
{
424
    return get_autopilot_id() != uint8_t(0);
136✔
425
}
426

427
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
428
{
429
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
430
}
431

432
bool SystemImpl::is_camera(uint8_t comp_id)
1✔
433
{
434
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
1✔
435
}
436

437
bool SystemImpl::has_camera(int camera_id) const
1✔
438
{
439
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
1✔
440

441
    if (camera_comp_id == -1) { // Check whether the system has any camera.
1✔
442
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
1✔
443
            return true;
1✔
444
        }
445
    } else { // Look for the camera whose id is `camera_id`.
446
        for (auto compid : _components) {
×
447
            if (compid == camera_comp_id) {
×
448
                return true;
×
449
            }
450
        }
451
    }
452
    return false;
×
453
}
454

455
bool SystemImpl::has_gimbal() const
×
456
{
457
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
458
}
459

460
bool SystemImpl::send_message(mavlink_message_t& message)
×
461
{
462
    return _mavsdk_impl.send_message(message);
×
463
}
464

465
bool SystemImpl::queue_message(
559✔
466
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
467
{
468
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
559✔
469
}
470

471
void SystemImpl::send_autopilot_version_request()
33✔
472
{
473
    MavlinkCommandSender::CommandLong command{};
33✔
474
    command.target_component_id = get_autopilot_id();
33✔
475

476
    if (_old_message_520_supported) {
33✔
477
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
478
        // release.
479
        command.command = MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES;
33✔
480
        command.params.maybe_param1 = 1.0f;
33✔
481
    } else {
482
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
483
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_AUTOPILOT_VERSION)};
×
484
    }
485

486
    send_command_async(command, [this](MavlinkCommandSender::Result result, float) {
33✔
487
        receive_autopilot_version_request_ack(result);
33✔
488
    });
33✔
489
}
33✔
490

491
void SystemImpl::receive_autopilot_version_request_ack(MavlinkCommandSender::Result result)
33✔
492
{
493
    if (result == MavlinkCommandSender::Result::Unsupported) {
33✔
NEW
494
        _old_message_520_supported = false;
×
NEW
495
        LogWarn()
×
NEW
496
            << "Trying alternative command REQUEST_MESSAGE instead of REQUEST_AUTOPILOT_CAPABILITIES next.";
×
497
    }
498
}
33✔
499

500
void SystemImpl::set_connected()
79✔
501
{
502
    bool enable_needed = false;
79✔
503
    {
504
        std::lock_guard<std::mutex> lock(_connection_mutex);
158✔
505

506
        if (!_connected) {
79✔
507
            if (!_components.empty()) {
69✔
508
                LogDebug() << "Discovered " << _components.size() << " component(s)";
69✔
509
            }
510

511
            _connected = true;
69✔
512

513
            // We call this later to avoid deadlocks on creating the server components.
514
            _mavsdk_impl.call_user_callback([this]() {
138✔
515
                // Send a heartbeat back immediately.
516
                _mavsdk_impl.start_sending_heartbeats();
517
            });
518

519
            register_timeout_handler(
69✔
520
                [this] { heartbeats_timed_out(); },
×
521
                HEARTBEAT_TIMEOUT_S,
522
                &_heartbeat_timeout_cookie);
523

524
            enable_needed = true;
69✔
525

526
            _is_connected_callbacks.queue(
69✔
527
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
528

529
        } else if (_connected) {
10✔
530
            refresh_timeout_handler(_heartbeat_timeout_cookie);
10✔
531
        }
532
        // If not yet connected there is nothing to do/
533
    }
534

535
    _mavsdk_impl.notify_on_discover();
79✔
536

537
    if (enable_needed) {
79✔
538
        if (has_autopilot()) {
69✔
539
            send_autopilot_version_request();
33✔
540
        }
541

542
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
138✔
543
        for (auto plugin_impl : _plugin_impls) {
69✔
544
            plugin_impl->enable();
×
545
        }
546
    }
547
}
79✔
548

549
void SystemImpl::set_disconnected()
×
550
{
551
    {
552
        std::lock_guard<std::mutex> lock(_connection_mutex);
×
553

554
        // This might not be needed because this is probably called from the triggered
555
        // timeout anyway, but it should also do no harm.
556
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
557
        //_heartbeat_timeout_cookie = nullptr;
558

559
        _connected = false;
×
560
        _is_connected_callbacks.queue(
×
561
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
562
    }
563
    _mavsdk_impl.notify_on_timeout();
×
564

565
    _mavsdk_impl.stop_sending_heartbeats();
×
566

567
    {
568
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
569
        for (auto plugin_impl : _plugin_impls) {
×
570
            plugin_impl->disable();
×
571
        }
572
    }
573
}
×
574

575
uint8_t SystemImpl::get_system_id() const
565✔
576
{
577
    return _target_address.system_id;
565✔
578
}
579

580
std::vector<uint8_t> SystemImpl::component_ids() const
×
581
{
582
    return std::vector<uint8_t>{_components.begin(), _components.end()};
×
583
}
584

585
void SystemImpl::set_system_id(uint8_t system_id)
×
586
{
587
    _target_address.system_id = system_id;
×
588
}
×
589

590
uint8_t SystemImpl::get_own_system_id() const
1,175✔
591
{
592
    return _mavsdk_impl.get_own_system_id();
1,175✔
593
}
594

595
uint8_t SystemImpl::get_own_component_id() const
1,175✔
596
{
597
    return _mavsdk_impl.get_own_component_id();
1,175✔
598
}
599

600
MAV_TYPE SystemImpl::get_vehicle_type() const
×
601
{
602
    return _vehicle_type;
×
603
}
604

605
uint8_t SystemImpl::get_own_mav_type() const
×
606
{
607
    return _mavsdk_impl.get_mav_type();
×
608
}
609

610
MavlinkParameterClient::Result SystemImpl::set_param(
×
611
    const std::string& name,
612
    ParamValue value,
613
    std::optional<uint8_t> maybe_component_id,
614
    bool extended)
615
{
616
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
617
        ->set_param(name, value);
×
618
}
619

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

627
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
628
    const std::string& name,
629
    int32_t value,
630
    std::optional<uint8_t> maybe_component_id,
631
    bool extended)
632
{
633
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
634
        ->set_param_int(name, value);
4✔
635
}
636

637
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
638
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
639
{
640
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
641
        ->set_param_custom(name, value);
4✔
642
}
643

644
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
645
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
646
{
647
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
648
        ->get_all_params();
8✔
649
}
650

651
void SystemImpl::set_param_async(
×
652
    const std::string& name,
653
    ParamValue value,
654
    const SetParamCallback& callback,
655
    const void* cookie,
656
    std::optional<uint8_t> maybe_component_id,
657
    bool extended)
658
{
659
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
660
        ->set_param_async(name, value, callback, cookie);
×
661
}
×
662

663
void SystemImpl::set_param_float_async(
×
664
    const std::string& name,
665
    float value,
666
    const SetParamCallback& callback,
667
    const void* cookie,
668
    std::optional<uint8_t> maybe_component_id,
669
    bool extended)
670
{
671
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
672
        ->set_param_float_async(name, value, callback, cookie);
×
673
}
×
674

675
void SystemImpl::set_param_int_async(
×
676
    const std::string& name,
677
    int32_t value,
678
    const SetParamCallback& callback,
679
    const void* cookie,
680
    std::optional<uint8_t> maybe_component_id,
681
    bool extended)
682
{
683
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
684
        ->set_param_int_async(name, value, callback, cookie);
×
685
}
×
686

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

694
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
695
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
696
{
697
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
698
        ->get_param_int(name);
10✔
699
}
700

701
std::pair<MavlinkParameterClient::Result, std::string>
702
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
703
{
704
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
705
        ->get_param_custom(name);
8✔
706
}
707

708
void SystemImpl::get_param_async(
×
709
    const std::string& name,
710
    ParamValue value,
711
    const GetParamAnyCallback& callback,
712
    const void* cookie,
713
    std::optional<uint8_t> maybe_component_id,
714
    bool extended)
715
{
716
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
717
        ->get_param_async(name, value, callback, cookie);
×
718
}
×
719

720
void SystemImpl::get_param_float_async(
×
721
    const std::string& name,
722
    const GetParamFloatCallback& callback,
723
    const void* cookie,
724
    std::optional<uint8_t> maybe_component_id,
725
    bool extended)
726
{
727
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
728
        ->get_param_float_async(name, callback, cookie);
×
729
}
×
730

731
void SystemImpl::get_param_int_async(
4✔
732
    const std::string& name,
733
    const GetParamIntCallback& callback,
734
    const void* cookie,
735
    std::optional<uint8_t> maybe_component_id,
736
    bool extended)
737
{
738
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
739
        ->get_param_int_async(name, callback, cookie);
4✔
740
}
4✔
741

742
void SystemImpl::get_param_custom_async(
×
743
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
744
{
745
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
746
}
×
747

748
void SystemImpl::cancel_all_param(const void* cookie)
2✔
749
{
750
    UNUSED(cookie);
2✔
751
    // FIXME: this currently crashes on destruction
752
    // param_sender(1, false)->cancel_all_param(cookie);
753
}
2✔
754

755
MavlinkCommandSender::Result
756
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
757
{
758
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
759
        make_command_flight_mode(system_mode, component_id);
×
760

761
    if (result.first != MavlinkCommandSender::Result::Success) {
×
762
        return result.first;
×
763
    }
764

765
    return send_command(result.second);
×
766
}
767

768
void SystemImpl::set_flight_mode_async(
×
769
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
770
{
771
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
772
        make_command_flight_mode(system_mode, component_id);
×
773

774
    if (result.first != MavlinkCommandSender::Result::Success) {
×
775
        if (callback) {
×
776
            callback(result.first, NAN);
×
777
        }
778
        return;
×
779
    }
780

781
    send_command_async(result.second, callback);
×
782
}
783

784
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
785
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
786
{
787
    if (_autopilot == Autopilot::ArduPilot) {
×
788
        return make_command_ardupilot_mode(flight_mode, component_id);
×
789
    } else {
790
        return make_command_px4_mode(flight_mode, component_id);
×
791
    }
792
}
793

794
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
795
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
796
{
797
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
798
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
799
    const uint8_t mode_type =
×
800
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
801

802
    MavlinkCommandSender::CommandLong command{};
×
803

804
    command.command = MAV_CMD_DO_SET_MODE;
×
805
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
806

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

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

857
        default:
×
858
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
859
                     << _vehicle_type;
×
860
            MavlinkCommandSender::CommandLong empty_command{};
×
861
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
862
    }
863
    command.target_component_id = component_id;
×
864

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

955
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
956
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
957
{
958
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
959
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
960

961
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
962

963
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
964
    //       but want to be rather safe than sorry.
965
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
966
    uint8_t custom_sub_mode = 0;
×
967

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

1014
    MavlinkCommandSender::CommandLong command{};
×
1015

1016
    command.command = MAV_CMD_DO_SET_MODE;
×
1017
    command.params.maybe_param1 = static_cast<float>(mode);
×
1018
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1019
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1020
    command.target_component_id = component_id;
×
1021

1022
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1023
}
1024

1025
FlightMode SystemImpl::get_flight_mode() const
6✔
1026
{
1027
    return _flight_mode;
6✔
1028
}
1029

1030
void SystemImpl::receive_float_param(
×
1031
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1032
{
1033
    if (callback) {
×
1034
        if (result == MavlinkParameterClient::Result::Success) {
×
1035
            callback(result, value.get<float>());
×
1036
        } else {
1037
            callback(result, NAN);
×
1038
        }
1039
    }
1040
}
×
1041

1042
void SystemImpl::receive_int_param(
×
1043
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1044
{
1045
    if (callback) {
×
1046
        if (result == MavlinkParameterClient::Result::Success) {
×
1047
            callback(result, value.get<int32_t>());
×
1048
        } else {
1049
            callback(result, 0);
×
1050
        }
1051
    }
1052
}
×
1053

1054
uint8_t SystemImpl::get_autopilot_id() const
213✔
1055
{
1056
    for (auto compid : _components)
255✔
1057
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
216✔
1058
            return compid;
174✔
1059
        }
1060
    // FIXME: Not sure what should be returned if autopilot is not found
1061
    return uint8_t(0);
39✔
1062
}
1063

1064
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1065
{
1066
    std::vector<uint8_t> camera_ids{};
×
1067

1068
    for (auto compid : _components)
×
1069
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1070
            camera_ids.push_back(compid);
×
1071
        }
1072
    return camera_ids;
×
1073
}
1074

1075
uint8_t SystemImpl::get_gimbal_id() const
×
1076
{
1077
    for (auto compid : _components)
×
1078
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1079
            return compid;
×
1080
        }
1081
    return uint8_t(0);
×
1082
}
1083

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

1093
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1094
{
1095
    if (_target_address.system_id == 0 && _components.empty()) {
×
1096
        return MavlinkCommandSender::Result::NoSystem;
×
1097
    }
1098
    command.target_system_id = get_system_id();
×
1099
    return _command_sender.send_command(command);
×
1100
}
1101

1102
void SystemImpl::send_command_async(
39✔
1103
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1104
{
1105
    if (_target_address.system_id == 0 && _components.empty()) {
39✔
1106
        if (callback) {
×
1107
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1108
        }
1109
        return;
×
1110
    }
1111
    command.target_system_id = get_system_id();
39✔
1112

1113
    _command_sender.queue_command_async(command, callback);
39✔
1114
}
1115

1116
void SystemImpl::send_command_async(
×
1117
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1118
{
1119
    if (_target_address.system_id == 0 && _components.empty()) {
×
1120
        if (callback) {
×
1121
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1122
        }
1123
        return;
×
1124
    }
1125
    command.target_system_id = get_system_id();
×
1126

1127
    _command_sender.queue_command_async(command, callback);
×
1128
}
1129

1130
MavlinkCommandSender::Result
1131
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1132
{
1133
    MavlinkCommandSender::CommandLong command =
×
1134
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1135
    return send_command(command);
×
1136
}
1137

1138
void SystemImpl::set_msg_rate_async(
1✔
1139
    uint16_t message_id,
1140
    double rate_hz,
1141
    const CommandResultCallback& callback,
1142
    uint8_t component_id)
1143
{
1144
    MavlinkCommandSender::CommandLong command =
1✔
1145
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1146
    send_command_async(command, callback);
1✔
1147
}
1✔
1148

1149
MavlinkCommandSender::CommandLong
1150
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1151
{
1152
    MavlinkCommandSender::CommandLong command{};
1✔
1153

1154
    // 0 to request default rate, -1 to stop stream
1155

1156
    float interval_us = 0.0f;
1✔
1157

1158
    if (rate_hz > 0) {
1✔
1159
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1160
    } else if (rate_hz < 0) {
×
1161
        interval_us = -1.0f;
×
1162
    }
1163

1164
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1165
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1166
    command.params.maybe_param2 = interval_us;
1✔
1167
    command.target_component_id = component_id;
1✔
1168

1169
    return command;
1✔
1170
}
1171

1172
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
37✔
1173
{
1174
    assert(plugin_impl);
37✔
1175

1176
    plugin_impl->init();
37✔
1177

1178
    {
1179
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
74✔
1180
        _plugin_impls.push_back(plugin_impl);
37✔
1181
    }
1182

1183
    // If we're connected already, let's enable it straightaway.
1184
    if (_connected) {
37✔
1185
        plugin_impl->enable();
37✔
1186
    }
1187
}
37✔
1188

1189
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
37✔
1190
{
1191
    assert(plugin_impl);
37✔
1192

1193
    plugin_impl->disable();
37✔
1194
    plugin_impl->deinit();
37✔
1195

1196
    // Remove first, so it won't get enabled/disabled anymore.
1197
    {
1198
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
74✔
1199
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
37✔
1200
        if (found != _plugin_impls.end()) {
37✔
1201
            _plugin_impls.erase(found);
37✔
1202
        }
1203
    }
1204
}
37✔
1205

1206
void SystemImpl::call_user_callback_located(
1,372✔
1207
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1208
{
1209
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
1,372✔
1210
}
1,372✔
1211

1212
void SystemImpl::param_changed(const std::string& name)
×
1213
{
1214
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1215

1216
    for (auto& callback : _param_changed_callbacks) {
×
1217
        callback.second(name);
×
1218
    }
1219
}
×
1220

1221
void SystemImpl::register_param_changed_handler(
1✔
1222
    const ParamChangedCallback& callback, const void* cookie)
1223
{
1224
    if (!callback) {
1✔
1225
        LogErr() << "No callback for param_changed_handler supplied.";
×
1226
        return;
×
1227
    }
1228

1229
    if (!cookie) {
1✔
1230
        LogErr() << "No callback for param_changed_handler supplied.";
×
1231
        return;
×
1232
    }
1233

1234
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
2✔
1235

1236
    _param_changed_callbacks[cookie] = callback;
1✔
1237
}
1238

1239
void SystemImpl::unregister_param_changed_handler(const void* cookie)
1✔
1240
{
1241
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
1✔
1242

1243
    auto it = _param_changed_callbacks.find(cookie);
1✔
1244
    if (it == _param_changed_callbacks.end()) {
1✔
1245
        LogWarn() << "param_changed_handler for cookie not found";
×
1246
        return;
×
1247
    }
1248
    _param_changed_callbacks.erase(it);
1✔
1249
}
1250

1251
Time& SystemImpl::get_time()
84✔
1252
{
1253
    return _mavsdk_impl.time;
84✔
1254
}
1255

1256
void SystemImpl::subscribe_param_float(
×
1257
    const std::string& name,
1258
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1259
    const void* cookie)
1260
{
1261
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1262
}
×
1263

1264
void SystemImpl::subscribe_param_int(
×
1265
    const std::string& name,
1266
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1267
    const void* cookie)
1268
{
1269
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1270
}
×
1271
void SystemImpl::subscribe_param_custom(
×
1272
    const std::string& name,
1273
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1274
    const void* cookie)
1275
{
1276
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1277
}
×
1278

1279
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
28✔
1280
{
1281
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
56✔
1282

1283
    for (auto& entry : _mavlink_parameter_clients) {
30✔
1284
        if (entry.component_id == component_id && entry.extended == extended) {
21✔
1285
            return entry.parameter_client.get();
19✔
1286
        }
1287
    }
1288

1289
    _mavlink_parameter_clients.push_back(
27✔
1290
        {std::make_unique<MavlinkParameterClient>(
1291
             _mavsdk_impl.default_server_component_impl().sender(),
9✔
1292
             _mavlink_message_handler,
9✔
1293
             _mavsdk_impl.timeout_handler,
9✔
1294
             [this]() { return timeout_s(); },
47✔
1295
             [this]() { return autopilot(); },
35✔
1296
             get_system_id(),
18✔
1297
             component_id,
1298
             extended),
1299
         component_id,
1300
         extended});
1301

1302
    return _mavlink_parameter_clients.back().parameter_client.get();
9✔
1303
}
1304

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