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

mavlink / MAVSDK / 6568658631

19 Oct 2023 01:31AM UTC coverage: 31.23% (+0.02%) from 31.215%
6568658631

push

github

web-flow
Merge pull request #2155 from mavlink/pr-static-fixes

Threading fixes, MAVLink sequence number cleanup

1386 of 1386 new or added lines in 46 files covered. (100.0%)

7906 of 25315 relevant lines covered (31.23%)

23.54 hits per line

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

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

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

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

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

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

57
    MavlinkChannels::Instance().checkin_used_channel(_channel);
20✔
58
}
20✔
59

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

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

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

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

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

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

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

104
void ServerComponentImpl::register_mavlink_message_handler(
×
105
    uint16_t msg_id, uint8_t cmp_id, const MavlinkMessageHandler& callback, const void* cookie)
106
{
107
    _mavsdk_impl.mavlink_message_handler.register_one(msg_id, cmp_id, callback, cookie);
×
108
}
×
109

110
void ServerComponentImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
111
{
112
    _mavsdk_impl.mavlink_message_handler.unregister_one(msg_id, cookie);
×
113
}
×
114

115
void ServerComponentImpl::unregister_all_mavlink_message_handlers(const void* cookie)
21✔
116
{
117
    _mavsdk_impl.mavlink_message_handler.unregister_all(cookie);
21✔
118
}
21✔
119

120
void ServerComponentImpl::do_work()
1,316✔
121
{
122
    _mavlink_parameter_server.do_work();
1,316✔
123
    _mission_transfer.do_work();
1,316✔
124
}
1,315✔
125

126
Sender& ServerComponentImpl::sender()
28✔
127
{
128
    return _our_sender;
28✔
129
}
130

131
uint8_t ServerComponentImpl::get_own_system_id() const
252✔
132
{
133
    return _mavsdk_impl.get_own_system_id();
252✔
134
}
135

136
void ServerComponentImpl::set_own_component_id(uint8_t own_component_id)
×
137
{
138
    _own_component_id = own_component_id;
×
139
}
×
140
uint8_t ServerComponentImpl::get_own_component_id() const
227✔
141
{
142
    return _own_component_id;
227✔
143
}
144

145
Time& ServerComponentImpl::get_time()
×
146
{
147
    return _mavsdk_impl.time;
×
148
}
149

150
bool ServerComponentImpl::send_message(mavlink_message_t& message)
×
151
{
152
    return _mavsdk_impl.send_message(message);
×
153
}
154

155
bool ServerComponentImpl::send_command_ack(mavlink_command_ack_t& command_ack)
×
156
{
157
    return queue_message([&, this](MavlinkAddress mavlink_address, uint8_t channel) {
×
158
        mavlink_message_t message;
159
        mavlink_msg_command_ack_encode_chan(
×
160
            mavlink_address.system_id,
×
161
            mavlink_address.component_id,
×
162
            channel,
163
            &message,
164
            &command_ack);
×
165
        return message;
×
166
    });
×
167
}
168

169
bool ServerComponentImpl::queue_message(
184✔
170
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
171
{
172
    std::lock_guard<std::mutex> lock(_mavlink_pack_mutex);
368✔
173
    MavlinkAddress mavlink_address{get_own_system_id(), get_own_component_id()};
184✔
174
    mavlink_message_t message = fun(mavlink_address, _channel);
184✔
175
    return _mavsdk_impl.send_message(message);
184✔
176
}
177

178
void ServerComponentImpl::add_call_every(
1✔
179
    std::function<void()> callback, float interval_s, void** cookie)
180
{
181
    _mavsdk_impl.call_every_handler.add(
2✔
182
        std::move(callback), static_cast<double>(interval_s), cookie);
1✔
183
}
1✔
184

185
void ServerComponentImpl::change_call_every(float interval_s, const void* cookie)
×
186
{
187
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
188
}
×
189

190
void ServerComponentImpl::reset_call_every(const void* cookie)
×
191
{
192
    _mavsdk_impl.call_every_handler.reset(cookie);
×
193
}
×
194

195
void ServerComponentImpl::remove_call_every(const void* cookie)
1✔
196
{
197
    _mavsdk_impl.call_every_handler.remove(cookie);
1✔
198
}
1✔
199

200
mavlink_command_ack_t ServerComponentImpl::make_command_ack_message(
14✔
201
    const MavlinkCommandReceiver::CommandLong& command, MAV_RESULT result)
202
{
203
    mavlink_command_ack_t command_ack{};
14✔
204
    command_ack.command = command.command;
14✔
205
    command_ack.result = result;
14✔
206
    command_ack.progress = std::numeric_limits<uint8_t>::max();
14✔
207
    command_ack.result_param2 = 0;
14✔
208
    command_ack.target_system = command.origin_system_id;
14✔
209
    command_ack.target_component = command.origin_component_id;
14✔
210

211
    return command_ack;
14✔
212
}
213

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

225
    return command_ack;
×
226
}
227

228
void ServerComponentImpl::send_heartbeat()
25✔
229
{
230
    queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
25✔
231
        mavlink_message_t message;
232
        mavlink_msg_heartbeat_pack_chan(
74✔
233
            get_own_system_id(),
101✔
234
            mavlink_address.component_id,
25✔
235
            channel,
236
            &message,
237
            _mavsdk_impl.get_mav_type(),
25✔
238
            mavlink_address.component_id == MAV_COMP_ID_AUTOPILOT1 ? MAV_AUTOPILOT_GENERIC :
25✔
239
                                                                     MAV_AUTOPILOT_INVALID,
240
            mavlink_address.component_id == MAV_COMP_ID_AUTOPILOT1 ? _base_mode.load() : 0,
38✔
241
            mavlink_address.component_id == MAV_COMP_ID_AUTOPILOT1 ? _custom_mode.load() : 0,
38✔
242
            get_system_status());
25✔
243
        return message;
25✔
244
    });
245
}
25✔
246

247
void ServerComponentImpl::set_system_status(uint8_t system_status)
×
248
{
249
    _system_status = static_cast<MAV_STATE>(system_status);
×
250
}
×
251

252
uint8_t ServerComponentImpl::get_system_status() const
25✔
253
{
254
    return _system_status;
25✔
255
}
256

257
void ServerComponentImpl::set_base_mode(uint8_t base_mode)
2✔
258
{
259
    _base_mode = base_mode;
2✔
260
}
2✔
261

262
uint8_t ServerComponentImpl::get_base_mode() const
2✔
263
{
264
    return _base_mode;
2✔
265
}
266

267
void ServerComponentImpl::set_custom_mode(uint32_t custom_mode)
×
268
{
269
    _custom_mode = custom_mode;
×
270
}
×
271

272
uint32_t ServerComponentImpl::get_custom_mode() const
×
273
{
274
    return _custom_mode;
×
275
}
276

277
void ServerComponentImpl::call_user_callback_located(
×
278
    const std::string& filename, const int linenumber, const std::function<void()>& func)
279
{
280
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
×
281
}
×
282

283
void ServerComponentImpl::register_timeout_handler(
×
284
    const std::function<void()>& callback, double duration_s, void** cookie)
285
{
286
    _mavsdk_impl.timeout_handler.add(callback, duration_s, cookie);
×
287
}
×
288

289
void ServerComponentImpl::refresh_timeout_handler(const void* cookie)
×
290
{
291
    _mavsdk_impl.timeout_handler.refresh(cookie);
×
292
}
×
293

294
void ServerComponentImpl::unregister_timeout_handler(const void* cookie)
×
295
{
296
    _mavsdk_impl.timeout_handler.remove(cookie);
×
297
}
×
298

299
void ServerComponentImpl::add_capabilities(uint64_t add_capabilities)
1✔
300
{
301
    {
302
        std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
1✔
303
        _autopilot_version.capabilities |= add_capabilities;
1✔
304
    }
305

306
    // We need to resend capabilities.
307
    send_autopilot_version();
1✔
308
}
1✔
309

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

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

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

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

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

340
void ServerComponentImpl::set_product_id(uint16_t product_id)
×
341
{
342
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
343
    _autopilot_version.product_id = product_id;
×
344
}
×
345

346
bool ServerComponentImpl::set_uid2(std::string uid2)
×
347
{
348
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
×
349
    if (uid2.size() > _autopilot_version.uid2.size()) {
×
350
        return false;
×
351
    }
352
    _autopilot_version.uid2 = {0};
×
353
    std::copy(uid2.begin(), uid2.end(), _autopilot_version.uid2.data());
×
354
    return true;
×
355
}
356

357
void ServerComponentImpl::send_autopilot_version()
12✔
358
{
359
    std::lock_guard<std::mutex> lock(_autopilot_version_mutex);
24✔
360
    const uint8_t custom_values[8] = {0}; // TO-DO: maybe?
12✔
361

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

385
ServerComponentImpl::OurSender::OurSender(ServerComponentImpl& server_component_impl) :
20✔
386
    _server_component_impl(server_component_impl)
20✔
387
{}
20✔
388

389
bool ServerComponentImpl::OurSender::send_message(mavlink_message_t& message)
×
390
{
391
    return _server_component_impl.send_message(message);
×
392
}
393

394
bool ServerComponentImpl::OurSender::queue_message(
114✔
395
    std::function<mavlink_message_t(MavlinkAddress, uint8_t)> fun)
396
{
397
    return _server_component_impl.queue_message(fun);
114✔
398
}
399

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

405
uint8_t ServerComponentImpl::OurSender::get_own_component_id() const
43✔
406
{
407
    return _server_component_impl.get_own_component_id();
43✔
408
}
409

410
Autopilot ServerComponentImpl::OurSender::autopilot() const
61✔
411
{
412
    // FIXME: hard-coded to PX4 for now to avoid the dependency into mavsdk_impl.
413
    return Autopilot::Px4;
61✔
414
}
415

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