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

mavlink / MAVSDK / 22201413014

19 Feb 2026 09:46PM UTC coverage: 48.99% (+0.02%) from 48.969%
22201413014

Pull #2774

github

web-flow
Merge 135f52158 into 7a91a339d
Pull Request #2774: docs: updates regarding cpp directory

18363 of 37483 relevant lines covered (48.99%)

671.27 hits per line

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

61.48
/cpp/src/mavsdk/core/server_component_impl.cpp
1
#include "server_component_impl.h"
2
#include "server_plugin_impl_base.h"
3
#include "mavsdk_impl.h"
4

5
namespace mavsdk {
6

7
ServerComponentImpl::ServerComponentImpl(
149✔
8
    MavsdkImpl& mavsdk_impl, uint8_t component_id, uint8_t mav_type) :
149✔
9
    _mavsdk_impl(mavsdk_impl),
149✔
10
    _own_component_id(component_id),
149✔
11
    _own_mav_type(mav_type),
149✔
12
    _our_sender(*this),
149✔
13
    _mavlink_command_receiver(*this),
149✔
14
    _mission_transfer_server(
298✔
15
        _our_sender,
16
        mavsdk_impl.mavlink_message_handler,
149✔
17
        mavsdk_impl.timeout_handler,
149✔
18
        [this]() { return _mavsdk_impl.timeout_s(); }),
8✔
19
    _mavlink_parameter_server(_our_sender, mavsdk_impl.mavlink_message_handler),
149✔
20
    _mavlink_request_message_handler(mavsdk_impl, *this, _mavlink_command_receiver),
149✔
21
    _mavlink_ftp_server(*this)
298✔
22
{
23
    _autopilot_version.capabilities |= MAV_PROTOCOL_CAPABILITY_MAVLINK2;
149✔
24

25
    if (!MavlinkChannels::Instance().checkout_free_channel(_channel)) {
149✔
26
        // We use a default of channel 0 which will still work but not track
27
        // seq correctly.
28
        _channel = 0;
×
29
        LogErr() << "Could not get a MAVLink channel, using default 0";
×
30
    }
31

32
    register_mavlink_command_handler(
149✔
33
        MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
34
        [this](const MavlinkCommandReceiver::CommandLong& command) {
×
35
            send_autopilot_version();
×
36
            return make_command_ack_message(command, MAV_RESULT_ACCEPTED);
×
37
        },
38
        this);
39

40
    register_mavlink_command_handler(
149✔
41
        MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
42
        [this](const MavlinkCommandReceiver::CommandInt& command) {
×
43
            send_autopilot_version();
×
44
            return make_command_ack_message(command, MAV_RESULT_ACCEPTED);
×
45
        },
46
        this);
47

48
    _mavlink_request_message_handler.register_handler(
149✔
49
        MAVLINK_MSG_ID_PROTOCOL_VERSION,
50
        [this](uint8_t, uint8_t, const MavlinkRequestMessageHandler::Params&) {
×
51
            send_protocol_version();
×
52
            return MAV_RESULT_ACCEPTED;
×
53
        },
54
        this);
55

56
    _mavlink_request_message_handler.register_handler(
149✔
57
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
58
        [this](uint8_t, uint8_t, const MavlinkRequestMessageHandler::Params&) {
67✔
59
            send_autopilot_version();
67✔
60
            return MAV_RESULT_ACCEPTED;
67✔
61
        },
62
        this);
63
}
149✔
64

65
ServerComponentImpl::~ServerComponentImpl()
149✔
66
{
67
    unregister_all_mavlink_command_handlers(this);
149✔
68
    _mavlink_request_message_handler.unregister_all_handlers(this);
149✔
69

70
    MavlinkChannels::Instance().checkin_used_channel(_channel);
149✔
71
}
149✔
72

73
void ServerComponentImpl::register_plugin(ServerPluginImplBase* server_plugin_impl)
58✔
74
{
75
    // This is a bit pointless now but just mirrors what is done for the client plugins.
76
    server_plugin_impl->init();
58✔
77
}
58✔
78

79
void ServerComponentImpl::unregister_plugin(ServerPluginImplBase* server_plugin_impl)
58✔
80
{
81
    // This is a bit pointless now but just mirrors what is done for the client plugins.
82
    server_plugin_impl->deinit();
58✔
83
}
58✔
84

85
void ServerComponentImpl::register_mavlink_command_handler(
149✔
86
    uint16_t cmd_id,
87
    const MavlinkCommandReceiver::MavlinkCommandIntHandler& callback,
88
    const void* cookie)
89
{
90
    _mavlink_command_receiver.register_mavlink_command_handler(cmd_id, callback, cookie);
149✔
91
}
149✔
92

93
void ServerComponentImpl::register_mavlink_command_handler(
380✔
94
    uint16_t cmd_id,
95
    const MavlinkCommandReceiver::MavlinkCommandLongHandler& callback,
96
    const void* cookie)
97
{
98
    _mavlink_command_receiver.register_mavlink_command_handler(cmd_id, callback, cookie);
380✔
99
}
380✔
100

101
void ServerComponentImpl::unregister_mavlink_command_handler(uint16_t cmd_id, const void* cookie)
12✔
102
{
103
    _mavlink_command_receiver.unregister_mavlink_command_handler(cmd_id, cookie);
12✔
104
}
12✔
105

106
void ServerComponentImpl::unregister_all_mavlink_command_handlers(const void* cookie)
309✔
107
{
108
    _mavlink_command_receiver.unregister_all_mavlink_command_handlers(cookie);
309✔
109
}
309✔
110

111
void ServerComponentImpl::register_mavlink_message_handler(
468✔
112
    uint16_t msg_id, const MavlinkMessageHandler& callback, const void* cookie)
113
{
114
    _mavsdk_impl.mavlink_message_handler.register_one(msg_id, callback, cookie);
468✔
115
}
468✔
116

117
void ServerComponentImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
118
{
119
    _mavsdk_impl.mavlink_message_handler.unregister_one(msg_id, cookie);
×
120
}
×
121

122
void ServerComponentImpl::unregister_all_mavlink_message_handlers(const void* cookie)
298✔
123
{
124
    _mavsdk_impl.mavlink_message_handler.unregister_all(cookie);
298✔
125
}
298✔
126

127
void ServerComponentImpl::unregister_all_mavlink_message_handlers_blocking(const void* cookie)
5✔
128
{
129
    _mavsdk_impl.mavlink_message_handler.unregister_all_blocking(cookie);
5✔
130
}
5✔
131

132
void ServerComponentImpl::do_work()
41,728✔
133
{
134
    _mavlink_parameter_server.do_work();
41,728✔
135
    _mission_transfer_server.do_work();
41,161✔
136
}
41,094✔
137

138
Sender& ServerComponentImpl::sender()
164✔
139
{
140
    return _our_sender;
164✔
141
}
142

143
uint8_t ServerComponentImpl::get_own_system_id() const
11,256✔
144
{
145
    return _mavsdk_impl.get_own_system_id();
11,256✔
146
}
147

148
void ServerComponentImpl::set_own_component_id(uint8_t own_component_id)
×
149
{
150
    _own_component_id = own_component_id;
×
151
}
×
152
uint8_t ServerComponentImpl::get_own_component_id() const
10,998✔
153
{
154
    return _own_component_id;
10,998✔
155
}
156

157
Time& ServerComponentImpl::get_time()
38✔
158
{
159
    return _mavsdk_impl.time;
38✔
160
}
161

162
bool ServerComponentImpl::send_message(mavlink_message_t& message)
×
163
{
164
    return _mavsdk_impl.send_message(message);
×
165
}
166

167
bool ServerComponentImpl::send_command_ack(mavlink_command_ack_t& command_ack)
31✔
168
{
169
    return queue_message([&, this](MavlinkAddress mavlink_address, uint8_t channel) {
62✔
170
        mavlink_message_t message;
171
        mavlink_msg_command_ack_encode_chan(
31✔
172
            mavlink_address.system_id,
31✔
173
            mavlink_address.component_id,
31✔
174
            channel,
175
            &message,
176
            &command_ack);
31✔
177
        return message;
31✔
178
    });
31✔
179
}
180

181
bool ServerComponentImpl::queue_message(
9,440✔
182
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
183
{
184
    std::lock_guard<std::mutex> lock(_mavlink_pack_mutex);
9,440✔
185
    MavlinkAddress mavlink_address{get_own_system_id(), get_own_component_id()};
9,443✔
186
    mavlink_message_t message = fun(mavlink_address, _channel);
9,443✔
187
    return _mavsdk_impl.send_message(message);
9,440✔
188
}
9,444✔
189

190
CallEveryHandler::Cookie
191
ServerComponentImpl::add_call_every(std::function<void()> callback, float interval_s)
2✔
192
{
193
    return _mavsdk_impl.call_every_handler.add(
4✔
194
        std::move(callback), static_cast<double>(interval_s));
4✔
195
}
196

197
void ServerComponentImpl::change_call_every(float interval_s, CallEveryHandler::Cookie cookie)
×
198
{
199
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
200
}
×
201

202
void ServerComponentImpl::reset_call_every(CallEveryHandler::Cookie cookie)
×
203
{
204
    _mavsdk_impl.call_every_handler.reset(cookie);
×
205
}
×
206

207
void ServerComponentImpl::remove_call_every(CallEveryHandler::Cookie cookie)
22✔
208
{
209
    _mavsdk_impl.call_every_handler.remove(cookie);
22✔
210
}
22✔
211

212
mavlink_command_ack_t ServerComponentImpl::make_command_ack_message(
242✔
213
    const MavlinkCommandReceiver::CommandLong& command, MAV_RESULT result)
214
{
215
    mavlink_command_ack_t command_ack{};
242✔
216
    command_ack.command = command.command;
242✔
217
    command_ack.result = result;
242✔
218
    command_ack.progress = std::numeric_limits<uint8_t>::max();
242✔
219
    command_ack.result_param2 = 0;
242✔
220
    command_ack.target_system = command.origin_system_id;
242✔
221
    command_ack.target_component = command.origin_component_id;
242✔
222

223
    return command_ack;
242✔
224
}
225

226
mavlink_command_ack_t ServerComponentImpl::make_command_ack_message(
×
227
    const MavlinkCommandReceiver::CommandInt& command, MAV_RESULT result)
228
{
229
    mavlink_command_ack_t command_ack{};
×
230
    command_ack.command = command.command;
×
231
    command_ack.result = result;
×
232
    command_ack.progress = std::numeric_limits<uint8_t>::max();
×
233
    command_ack.result_param2 = 0;
×
234
    command_ack.target_system = command.origin_system_id;
×
235
    command_ack.target_component = command.origin_component_id;
×
236

237
    return command_ack;
×
238
}
239

240
void ServerComponentImpl::send_heartbeat()
489✔
241
{
242
    queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
489✔
243
        mavlink_message_t message;
244
        mavlink_msg_heartbeat_pack_chan(
1,429✔
245
            get_own_system_id(),
1,746✔
246
            mavlink_address.component_id,
486✔
247
            channel,
248
            &message,
249
            _own_mav_type,
486✔
250
            mavlink_address.component_id == MAV_COMP_ID_AUTOPILOT1 ?
486✔
251
                _mavsdk_impl.get_mav_autopilot() :
258✔
252
                static_cast<uint8_t>(MAV_AUTOPILOT_INVALID),
253
            mavlink_address.component_id == MAV_COMP_ID_AUTOPILOT1 ? _base_mode.load() : 0,
744✔
254
            mavlink_address.component_id == MAV_COMP_ID_AUTOPILOT1 ? _custom_mode.load() : 0,
743✔
255
            get_system_status());
487✔
256
        return message;
486✔
257
    });
258
}
484✔
259

260
void ServerComponentImpl::set_system_status(uint8_t system_status)
×
261
{
262
    _system_status = static_cast<MAV_STATE>(system_status);
×
263
}
×
264

265
uint8_t ServerComponentImpl::get_system_status() const
489✔
266
{
267
    return _system_status;
489✔
268
}
269

270
void ServerComponentImpl::set_base_mode(uint8_t base_mode)
2✔
271
{
272
    _base_mode = base_mode;
2✔
273
}
2✔
274

275
uint8_t ServerComponentImpl::get_base_mode() const
2✔
276
{
277
    return _base_mode;
2✔
278
}
279

280
void ServerComponentImpl::set_custom_mode(uint32_t custom_mode)
×
281
{
282
    _custom_mode = custom_mode;
×
283
}
×
284

285
uint32_t ServerComponentImpl::get_custom_mode() const
×
286
{
287
    return _custom_mode;
×
288
}
289

290
void ServerComponentImpl::call_user_callback_located(
10✔
291
    const std::string& filename, const int linenumber, const std::function<void()>& func)
292
{
293
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
10✔
294
}
10✔
295

296
TimeoutHandler::Cookie ServerComponentImpl::register_timeout_handler(
×
297
    const std::function<void()>& callback, double duration_s)
298
{
299
    return _mavsdk_impl.timeout_handler.add(callback, duration_s);
×
300
}
301

302
void ServerComponentImpl::refresh_timeout_handler(TimeoutHandler::Cookie cookie)
×
303
{
304
    _mavsdk_impl.timeout_handler.refresh(cookie);
×
305
}
×
306

307
void ServerComponentImpl::unregister_timeout_handler(TimeoutHandler::Cookie cookie)
×
308
{
309
    _mavsdk_impl.timeout_handler.remove(cookie);
×
310
}
×
311

312
void ServerComponentImpl::add_capabilities(uint64_t add_capabilities)
5✔
313
{
314
    {
315
        std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
5✔
316
        _autopilot_version.capabilities |= add_capabilities;
5✔
317
    }
5✔
318

319
    // We need to resend capabilities.
320
    send_autopilot_version();
5✔
321
}
5✔
322

323
void ServerComponentImpl::set_flight_sw_version(uint32_t flight_sw_version)
×
324
{
325
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
326
    _autopilot_version.flight_sw_version = flight_sw_version;
×
327
}
×
328

329
void ServerComponentImpl::set_middleware_sw_version(uint32_t middleware_sw_version)
×
330
{
331
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
332
    _autopilot_version.middleware_sw_version = middleware_sw_version;
×
333
}
×
334

335
void ServerComponentImpl::set_os_sw_version(uint32_t os_sw_version)
×
336
{
337
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
338
    _autopilot_version.os_sw_version = os_sw_version;
×
339
}
×
340

341
void ServerComponentImpl::set_board_version(uint32_t board_version)
×
342
{
343
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
344
    _autopilot_version.board_version = board_version;
×
345
}
×
346

347
void ServerComponentImpl::set_vendor_id(uint16_t vendor_id)
×
348
{
349
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
350
    _autopilot_version.vendor_id = vendor_id;
×
351
}
×
352

353
void ServerComponentImpl::set_product_id(uint16_t product_id)
×
354
{
355
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
356
    _autopilot_version.product_id = product_id;
×
357
}
×
358

359
bool ServerComponentImpl::set_uid2(std::string uid2)
×
360
{
361
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
362
    if (uid2.size() > _autopilot_version.uid2.size()) {
×
363
        return false;
×
364
    }
365
    _autopilot_version.uid2 = {0};
×
366
    std::copy(uid2.begin(), uid2.end(), _autopilot_version.uid2.data());
×
367
    return true;
×
368
}
×
369

370
void ServerComponentImpl::send_autopilot_version()
73✔
371
{
372
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
73✔
373
    const uint8_t custom_values[8] = {0}; // TO-DO: maybe?
73✔
374

375
    queue_message([&, this](MavlinkAddress mavlink_address, uint8_t channel) {
73✔
376
        mavlink_message_t message;
377
        mavlink_msg_autopilot_version_pack_chan(
73✔
378
            mavlink_address.system_id,
73✔
379
            mavlink_address.component_id,
73✔
380
            channel,
381
            &message,
382
            _autopilot_version.capabilities,
383
            _autopilot_version.flight_sw_version,
384
            _autopilot_version.middleware_sw_version,
385
            _autopilot_version.os_sw_version,
386
            _autopilot_version.board_version,
387
            custom_values,
73✔
388
            custom_values,
389
            custom_values,
390
            _autopilot_version.vendor_id,
73✔
391
            _autopilot_version.product_id,
73✔
392
            0,
393
            _autopilot_version.uid2.data());
73✔
394
        return message;
73✔
395
    });
396
}
73✔
397

398
void ServerComponentImpl::send_protocol_version()
×
399
{
400
    queue_message([&, this](MavlinkAddress mavlink_address, uint8_t channel) {
×
401
        mavlink_message_t message;
402
        mavlink_msg_protocol_version_pack_chan(
×
403
            mavlink_address.system_id,
×
404
            mavlink_address.component_id,
×
405
            channel,
406
            &message,
407
            MAVLINK_VERSION_INFO.version,
×
408
            MAVLINK_VERSION_INFO.min_version,
×
409
            MAVLINK_VERSION_INFO.max_version,
×
410
            MAVLINK_VERSION_INFO.spec_version_hash,
411
            MAVLINK_VERSION_INFO.library_version_hash);
412
        return message;
×
413
    });
414
}
×
415

416
ServerComponentImpl::OurSender::OurSender(ServerComponentImpl& server_component_impl) :
149✔
417
    _server_component_impl(server_component_impl)
149✔
418
{}
149✔
419

420
bool ServerComponentImpl::OurSender::send_message(mavlink_message_t& message)
×
421
{
422
    return _server_component_impl.send_message(message);
×
423
}
424

425
bool ServerComponentImpl::OurSender::queue_message(
6,940✔
426
    std::function<mavlink_message_t(MavlinkAddress, uint8_t)> fun)
427
{
428
    return _server_component_impl.queue_message(fun);
6,940✔
429
}
430

431
uint8_t ServerComponentImpl::OurSender::get_own_system_id() const
77✔
432
{
433
    return _server_component_impl.get_own_system_id();
77✔
434
}
435

436
uint8_t ServerComponentImpl::OurSender::get_own_component_id() const
77✔
437
{
438
    return _server_component_impl.get_own_component_id();
77✔
439
}
440

441
CompatibilityMode ServerComponentImpl::OurSender::compatibility_mode() const
39✔
442
{
443
    return _server_component_impl._mavsdk_impl.get_compatibility_mode();
39✔
444
}
445

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