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

mavlink / MAVSDK / 11767930807

10 Nov 2024 07:33PM UTC coverage: 38.608% (+0.7%) from 37.921%
11767930807

push

github

web-flow
Merge pull request #2394 from mavlink/pr-consolidate-ci

Consolidate CI

12030 of 31159 relevant lines covered (38.61%)

243.33 hits per line

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

58.74
/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(MavsdkImpl& mavsdk_impl, uint8_t component_id) :
72✔
8
    _mavsdk_impl(mavsdk_impl),
72✔
9
    _own_component_id(component_id),
72✔
10
    _our_sender(*this),
72✔
11
    _mavlink_command_receiver(*this),
72✔
12
    _mission_transfer_server(
144✔
13
        _our_sender,
14
        mavsdk_impl.mavlink_message_handler,
72✔
15
        mavsdk_impl.timeout_handler,
72✔
16
        [this]() { return _mavsdk_impl.timeout_s(); }),
1✔
17
    _mavlink_parameter_server(_our_sender, mavsdk_impl.mavlink_message_handler),
72✔
18
    _mavlink_request_message_handler(mavsdk_impl, *this, _mavlink_command_receiver),
72✔
19
    _mavlink_ftp_server(*this)
144✔
20
{
21
    if (!MavlinkChannels::Instance().checkout_free_channel(_channel)) {
72✔
22
        // We use a default of channel 0 which will still work but not track
23
        // seq correctly.
24
        _channel = 0;
×
25
        LogErr() << "Could not get a MAVLink channel, using default 0";
×
26
    }
27

28
    register_mavlink_command_handler(
72✔
29
        MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
30
        [this](const MavlinkCommandReceiver::CommandLong& command) {
4✔
31
            send_autopilot_version();
2✔
32
            return make_command_ack_message(command, MAV_RESULT_ACCEPTED);
2✔
33
        },
34
        this);
35

36
    register_mavlink_command_handler(
72✔
37
        MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
38
        [this](const MavlinkCommandReceiver::CommandInt& command) {
×
39
            send_autopilot_version();
×
40
            return make_command_ack_message(command, MAV_RESULT_ACCEPTED);
×
41
        },
42
        this);
43

44
    _mavlink_request_message_handler.register_handler(
72✔
45
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
46
        [this](uint8_t, uint8_t, const MavlinkRequestMessageHandler::Params&) {
33✔
47
            send_autopilot_version();
33✔
48
            return MAV_RESULT_ACCEPTED;
33✔
49
        },
50
        this);
51
}
72✔
52

53
ServerComponentImpl::~ServerComponentImpl()
72✔
54
{
55
    unregister_all_mavlink_command_handlers(this);
72✔
56
    _mavlink_request_message_handler.unregister_all_handlers(this);
72✔
57

58
    MavlinkChannels::Instance().checkin_used_channel(_channel);
72✔
59
}
72✔
60

61
void ServerComponentImpl::register_plugin(ServerPluginImplBase* server_plugin_impl)
35✔
62
{
63
    // This is a bit pointless now but just mirrors what is done for the client plugins.
64
    server_plugin_impl->init();
35✔
65
}
35✔
66

67
void ServerComponentImpl::unregister_plugin(ServerPluginImplBase* server_plugin_impl)
35✔
68
{
69
    // This is a bit pointless now but just mirrors what is done for the client plugins.
70
    server_plugin_impl->deinit();
35✔
71
}
35✔
72

73
void ServerComponentImpl::register_mavlink_command_handler(
72✔
74
    uint16_t cmd_id,
75
    const MavlinkCommandReceiver::MavlinkCommandIntHandler& callback,
76
    const void* cookie)
77
{
78
    _mavlink_command_receiver.register_mavlink_command_handler(cmd_id, callback, cookie);
72✔
79
}
72✔
80

81
void ServerComponentImpl::register_mavlink_command_handler(
100✔
82
    uint16_t cmd_id,
83
    const MavlinkCommandReceiver::MavlinkCommandLongHandler& callback,
84
    const void* cookie)
85
{
86
    _mavlink_command_receiver.register_mavlink_command_handler(cmd_id, callback, cookie);
100✔
87
}
100✔
88

89
void ServerComponentImpl::unregister_mavlink_command_handler(uint16_t cmd_id, const void* cookie)
×
90
{
91
    _mavlink_command_receiver.unregister_mavlink_command_handler(cmd_id, cookie);
×
92
}
×
93

94
void ServerComponentImpl::unregister_all_mavlink_command_handlers(const void* cookie)
146✔
95
{
96
    _mavlink_command_receiver.unregister_all_mavlink_command_handlers(cookie);
146✔
97
}
146✔
98

99
void ServerComponentImpl::register_mavlink_message_handler(
219✔
100
    uint16_t msg_id, const MavlinkMessageHandler& callback, const void* cookie)
101
{
102
    _mavsdk_impl.mavlink_message_handler.register_one(msg_id, callback, cookie);
219✔
103
}
219✔
104

105
void ServerComponentImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
106
{
107
    _mavsdk_impl.mavlink_message_handler.unregister_one(msg_id, cookie);
×
108
}
×
109

110
void ServerComponentImpl::unregister_all_mavlink_message_handlers(const void* cookie)
145✔
111
{
112
    _mavsdk_impl.mavlink_message_handler.unregister_all(cookie);
145✔
113
}
145✔
114

115
void ServerComponentImpl::do_work()
11,804✔
116
{
117
    _mavlink_parameter_server.do_work();
11,804✔
118
    _mission_transfer_server.do_work();
11,464✔
119
}
11,547✔
120

121
Sender& ServerComponentImpl::sender()
77✔
122
{
123
    return _our_sender;
77✔
124
}
125

126
uint8_t ServerComponentImpl::get_own_system_id() const
3,042✔
127
{
128
    return _mavsdk_impl.get_own_system_id();
3,042✔
129
}
130

131
void ServerComponentImpl::set_own_component_id(uint8_t own_component_id)
×
132
{
133
    _own_component_id = own_component_id;
×
134
}
×
135
uint8_t ServerComponentImpl::get_own_component_id() const
2,922✔
136
{
137
    return _own_component_id;
2,922✔
138
}
139

140
Time& ServerComponentImpl::get_time()
1✔
141
{
142
    return _mavsdk_impl.time;
1✔
143
}
144

145
bool ServerComponentImpl::send_message(mavlink_message_t& message)
×
146
{
147
    return _mavsdk_impl.send_message(message);
×
148
}
149

150
bool ServerComponentImpl::send_command_ack(mavlink_command_ack_t& command_ack)
×
151
{
152
    return queue_message([&, this](MavlinkAddress mavlink_address, uint8_t channel) {
×
153
        mavlink_message_t message;
154
        mavlink_msg_command_ack_encode_chan(
×
155
            mavlink_address.system_id,
×
156
            mavlink_address.component_id,
×
157
            channel,
158
            &message,
159
            &command_ack);
×
160
        return message;
×
161
    });
×
162
}
163

164
bool ServerComponentImpl::queue_message(
1,663✔
165
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
166
{
167
    std::lock_guard<std::mutex> lock(_mavlink_pack_mutex);
1,663✔
168
    MavlinkAddress mavlink_address{get_own_system_id(), get_own_component_id()};
1,663✔
169
    mavlink_message_t message = fun(mavlink_address, _channel);
1,663✔
170
    return _mavsdk_impl.send_message(message);
1,663✔
171
}
1,663✔
172

173
CallEveryHandler::Cookie
174
ServerComponentImpl::add_call_every(std::function<void()> callback, float interval_s)
1✔
175
{
176
    return _mavsdk_impl.call_every_handler.add(
2✔
177
        std::move(callback), static_cast<double>(interval_s));
1✔
178
}
179

180
void ServerComponentImpl::change_call_every(float interval_s, CallEveryHandler::Cookie cookie)
×
181
{
182
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
183
}
×
184

185
void ServerComponentImpl::reset_call_every(CallEveryHandler::Cookie cookie)
×
186
{
187
    _mavsdk_impl.call_every_handler.reset(cookie);
×
188
}
×
189

190
void ServerComponentImpl::remove_call_every(CallEveryHandler::Cookie cookie)
2✔
191
{
192
    _mavsdk_impl.call_every_handler.remove(cookie);
2✔
193
}
2✔
194

195
mavlink_command_ack_t ServerComponentImpl::make_command_ack_message(
40✔
196
    const MavlinkCommandReceiver::CommandLong& command, MAV_RESULT result)
197
{
198
    mavlink_command_ack_t command_ack{};
40✔
199
    command_ack.command = command.command;
40✔
200
    command_ack.result = result;
40✔
201
    command_ack.progress = std::numeric_limits<uint8_t>::max();
40✔
202
    command_ack.result_param2 = 0;
40✔
203
    command_ack.target_system = command.origin_system_id;
40✔
204
    command_ack.target_component = command.origin_component_id;
40✔
205

206
    return command_ack;
40✔
207
}
208

209
mavlink_command_ack_t ServerComponentImpl::make_command_ack_message(
×
210
    const MavlinkCommandReceiver::CommandInt& command, MAV_RESULT result)
211
{
212
    mavlink_command_ack_t command_ack{};
×
213
    command_ack.command = command.command;
×
214
    command_ack.result = result;
×
215
    command_ack.progress = std::numeric_limits<uint8_t>::max();
×
216
    command_ack.result_param2 = 0;
×
217
    command_ack.target_system = command.origin_system_id;
×
218
    command_ack.target_component = command.origin_component_id;
×
219

220
    return command_ack;
×
221
}
222

223
void ServerComponentImpl::send_heartbeat()
162✔
224
{
225
    queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
162✔
226
        mavlink_message_t message;
227
        mavlink_msg_heartbeat_pack_chan(
422✔
228
            get_own_system_id(),
712✔
229
            mavlink_address.component_id,
162✔
230
            channel,
231
            &message,
232
            _mavsdk_impl.get_mav_type(),
162✔
233
            mavlink_address.component_id == MAV_COMP_ID_AUTOPILOT1 ? MAV_AUTOPILOT_GENERIC :
162✔
234
                                                                     MAV_AUTOPILOT_INVALID,
235
            mavlink_address.component_id == MAV_COMP_ID_AUTOPILOT1 ? _base_mode.load() : 0,
275✔
236
            mavlink_address.component_id == MAV_COMP_ID_AUTOPILOT1 ? _custom_mode.load() : 0,
275✔
237
            get_system_status());
162✔
238
        return message;
162✔
239
    });
240
}
162✔
241

242
void ServerComponentImpl::set_system_status(uint8_t system_status)
×
243
{
244
    _system_status = static_cast<MAV_STATE>(system_status);
×
245
}
×
246

247
uint8_t ServerComponentImpl::get_system_status() const
162✔
248
{
249
    return _system_status;
162✔
250
}
251

252
void ServerComponentImpl::set_base_mode(uint8_t base_mode)
2✔
253
{
254
    _base_mode = base_mode;
2✔
255
}
2✔
256

257
uint8_t ServerComponentImpl::get_base_mode() const
2✔
258
{
259
    return _base_mode;
2✔
260
}
261

262
void ServerComponentImpl::set_custom_mode(uint32_t custom_mode)
×
263
{
264
    _custom_mode = custom_mode;
×
265
}
×
266

267
uint32_t ServerComponentImpl::get_custom_mode() const
×
268
{
269
    return _custom_mode;
×
270
}
271

272
void ServerComponentImpl::call_user_callback_located(
×
273
    const std::string& filename, const int linenumber, const std::function<void()>& func)
274
{
275
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
×
276
}
×
277

278
TimeoutHandler::Cookie ServerComponentImpl::register_timeout_handler(
×
279
    const std::function<void()>& callback, double duration_s)
280
{
281
    return _mavsdk_impl.timeout_handler.add(callback, duration_s);
×
282
}
283

284
void ServerComponentImpl::refresh_timeout_handler(TimeoutHandler::Cookie cookie)
×
285
{
286
    _mavsdk_impl.timeout_handler.refresh(cookie);
×
287
}
×
288

289
void ServerComponentImpl::unregister_timeout_handler(TimeoutHandler::Cookie cookie)
×
290
{
291
    _mavsdk_impl.timeout_handler.remove(cookie);
×
292
}
×
293

294
void ServerComponentImpl::add_capabilities(uint64_t add_capabilities)
1✔
295
{
296
    {
297
        std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
1✔
298
        _autopilot_version.capabilities |= add_capabilities;
1✔
299
    }
1✔
300

301
    // We need to resend capabilities.
302
    send_autopilot_version();
1✔
303
}
1✔
304

305
void ServerComponentImpl::set_flight_sw_version(uint32_t flight_sw_version)
×
306
{
307
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
308
    _autopilot_version.flight_sw_version = flight_sw_version;
×
309
}
×
310

311
void ServerComponentImpl::set_middleware_sw_version(uint32_t middleware_sw_version)
×
312
{
313
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
314
    _autopilot_version.middleware_sw_version = middleware_sw_version;
×
315
}
×
316

317
void ServerComponentImpl::set_os_sw_version(uint32_t os_sw_version)
×
318
{
319
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
320
    _autopilot_version.os_sw_version = os_sw_version;
×
321
}
×
322

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

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

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

341
bool ServerComponentImpl::set_uid2(std::string uid2)
×
342
{
343
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
344
    if (uid2.size() > _autopilot_version.uid2.size()) {
×
345
        return false;
×
346
    }
347
    _autopilot_version.uid2 = {0};
×
348
    std::copy(uid2.begin(), uid2.end(), _autopilot_version.uid2.data());
×
349
    return true;
×
350
}
×
351

352
void ServerComponentImpl::send_autopilot_version()
38✔
353
{
354
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
38✔
355
    const uint8_t custom_values[8] = {0}; // TO-DO: maybe?
38✔
356

357
    queue_message([&, this](MavlinkAddress mavlink_address, uint8_t channel) {
38✔
358
        mavlink_message_t message;
359
        mavlink_msg_autopilot_version_pack_chan(
38✔
360
            mavlink_address.system_id,
38✔
361
            mavlink_address.component_id,
38✔
362
            channel,
363
            &message,
364
            _autopilot_version.capabilities,
365
            _autopilot_version.flight_sw_version,
366
            _autopilot_version.middleware_sw_version,
367
            _autopilot_version.os_sw_version,
368
            _autopilot_version.board_version,
369
            custom_values,
38✔
370
            custom_values,
371
            custom_values,
372
            _autopilot_version.vendor_id,
38✔
373
            _autopilot_version.product_id,
38✔
374
            0,
375
            _autopilot_version.uid2.data());
38✔
376
        return message;
38✔
377
    });
378
}
38✔
379

380
ServerComponentImpl::OurSender::OurSender(ServerComponentImpl& server_component_impl) :
72✔
381
    _server_component_impl(server_component_impl)
72✔
382
{}
72✔
383

384
bool ServerComponentImpl::OurSender::send_message(mavlink_message_t& message)
×
385
{
386
    return _server_component_impl.send_message(message);
×
387
}
388

389
bool ServerComponentImpl::OurSender::queue_message(
116✔
390
    std::function<mavlink_message_t(MavlinkAddress, uint8_t)> fun)
391
{
392
    return _server_component_impl.queue_message(fun);
116✔
393
}
394

395
uint8_t ServerComponentImpl::OurSender::get_own_system_id() const
43✔
396
{
397
    return _server_component_impl.get_own_system_id();
43✔
398
}
399

400
uint8_t ServerComponentImpl::OurSender::get_own_component_id() const
43✔
401
{
402
    return _server_component_impl.get_own_component_id();
43✔
403
}
404

405
Autopilot ServerComponentImpl::OurSender::autopilot() const
30✔
406
{
407
    // FIXME: hard-coded to PX4 for now to avoid the dependency into mavsdk_impl.
408
    return Autopilot::Px4;
30✔
409
}
410

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