/
mavlink_parameters.cpp
474 lines (397 loc) · 16.4 KB
/
mavlink_parameters.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
#include "mavlink_parameters.h"
#include "system_impl.h"
#include <future>
namespace dronecode_sdk {
MAVLinkParameters::MAVLinkParameters(SystemImpl &parent) : _parent(parent)
{
_parent.register_mavlink_message_handler(
MAVLINK_MSG_ID_PARAM_VALUE,
std::bind(&MAVLinkParameters::process_param_value, this, std::placeholders::_1),
this);
_parent.register_mavlink_message_handler(
MAVLINK_MSG_ID_PARAM_EXT_VALUE,
std::bind(&MAVLinkParameters::process_param_ext_value, this, std::placeholders::_1),
this);
_parent.register_mavlink_message_handler(
MAVLINK_MSG_ID_PARAM_EXT_ACK,
std::bind(&MAVLinkParameters::process_param_ext_ack, this, std::placeholders::_1),
this);
}
MAVLinkParameters::~MAVLinkParameters()
{
_parent.unregister_all_mavlink_message_handlers(this);
}
void MAVLinkParameters::set_param_async(const std::string &name,
const ParamValue &value,
set_param_callback_t callback,
bool extended)
{
// if (value.is_float()) {
// LogDebug() << "setting param " << name << " to " << value.get_float();
// } else {
// LogDebug() << "setting param " << name << " to " << value.get_int();
// }
if (name.size() > PARAM_ID_LEN) {
LogErr() << "Error: param name too long";
if (callback) {
callback(false);
}
return;
}
SetParamWork new_work;
new_work.callback = callback;
new_work.param_name = name;
new_work.param_value = value;
new_work.extended = extended;
_set_param_queue.push_back(new_work);
}
bool MAVLinkParameters::set_param(const std::string &name, const ParamValue &value, bool extended)
{
auto prom = std::make_shared<std::promise<bool>>();
auto res = prom->get_future();
set_param_async(name, value, [&prom](bool success) { prom->set_value(success); }, extended);
return res.get();
}
void MAVLinkParameters::get_param_async(const std::string &name,
get_param_callback_t callback,
bool extended)
{
// LogDebug() << "getting param " << name << ", extended: " << (extended ? "yes" : "no");
if (name.size() > PARAM_ID_LEN) {
LogErr() << "Error: param name too long";
if (callback) {
ParamValue empty_param;
callback(false, empty_param);
}
return;
}
// Use cached value if available.
if (_cache.find(name) != _cache.end()) {
if (callback) {
callback(true, _cache[name]);
}
return;
}
// Otherwise push work onto queue.
GetParamWork new_work;
new_work.callback = callback;
new_work.param_name = name;
new_work.extended = extended;
_get_param_queue.push_back(new_work);
}
std::pair<bool, MAVLinkParameters::ParamValue> MAVLinkParameters::get_param(const std::string &name,
bool extended)
{
auto prom = std::make_shared<std::promise<std::pair<bool, MAVLinkParameters::ParamValue>>>();
auto res = prom->get_future();
get_param_async(name,
[&prom](bool success, ParamValue value) {
prom->set_value(std::make_pair<>(success, value));
},
extended);
return res.get();
}
void MAVLinkParameters::do_work()
{
std::lock_guard<std::mutex> lock(_state_mutex);
if (_state != State::NONE) {
// If we're still busy, let's wait
return;
}
auto set_param_work = _set_param_queue.borrow_front();
auto get_param_work = _get_param_queue.borrow_front();
if (!set_param_work && !get_param_work) {
return;
}
// There params to set which we always do first
if (set_param_work) {
// We don't need get_param_work and can give it back.
_get_param_queue.return_front();
// We need to wait for this param to get sent back as confirmation.
_state = State::SET_PARAM_BUSY;
char param_id[PARAM_ID_LEN] = {};
STRNCPY(param_id, set_param_work->param_name.c_str(), sizeof(param_id) - 1);
mavlink_message_t message = {};
if (set_param_work->extended) {
char param_value_buf[128] = {};
set_param_work->param_value.get_128_bytes(param_value_buf);
// FIXME: extended currently always go to the camera component
mavlink_msg_param_ext_set_pack(GCSClient::system_id,
GCSClient::component_id,
&message,
_parent.get_system_id(),
MAV_COMP_ID_CAMERA,
param_id,
param_value_buf,
set_param_work->param_value.get_mav_param_ext_type());
} else {
// Param set is intended for Autopilot only.
mavlink_msg_param_set_pack(GCSClient::system_id,
GCSClient::component_id,
&message,
_parent.get_system_id(),
_parent.get_autopilot_id(),
param_id,
set_param_work->param_value.get_4_float_bytes(),
set_param_work->param_value.get_mav_param_type());
}
if (!_parent.send_message(message)) {
LogErr() << "Error: Send message failed";
if (set_param_work->callback) {
set_param_work->callback(false);
}
_state = State::NONE;
_set_param_queue.pop_front();
return;
}
// _last_request_time = _parent.get_time().steady_time();
// We want to get notified if a timeout happens
_parent.register_timeout_handler(
std::bind(&MAVLinkParameters::receive_timeout, this), 0.5, &_timeout_cookie);
_set_param_queue.return_front();
} else {
_set_param_queue.return_front();
// The busy flag gets reset when the param comes in
// or after a timeout.
_state = State::GET_PARAM_BUSY;
char param_id[PARAM_ID_LEN] = {};
STRNCPY(param_id, get_param_work->param_name.c_str(), sizeof(param_id) - 1);
// LogDebug() << "now getting: " << get_param_work->param_name;
mavlink_message_t message = {};
if (get_param_work->extended) {
mavlink_msg_param_ext_request_read_pack(GCSClient::system_id,
GCSClient::component_id,
&message,
_parent.get_system_id(),
MAV_COMP_ID_CAMERA,
param_id,
-1);
} else {
// LogDebug() << "request read: "
// << (int)GCSClient::system_id << ":"
// << (int)GCSClient::component_id <<
// " to "
// << (int)_parent.get_system_id() << ":"
// << (int)_parent.get_autopilot_id();
mavlink_msg_param_request_read_pack(GCSClient::system_id,
GCSClient::component_id,
&message,
_parent.get_system_id(),
_parent.get_autopilot_id(),
param_id,
-1);
}
if (!_parent.send_message(message)) {
LogErr() << "Error: Send message failed";
if (get_param_work->callback) {
ParamValue empty_param;
get_param_work->callback(false, empty_param);
}
_state = State::NONE;
_get_param_queue.pop_front();
return;
}
// _last_request_time = _parent.get_time().steady_time();
// We want to get notified if a timeout happens
_parent.register_timeout_handler(
std::bind(&MAVLinkParameters::receive_timeout, this), 0.5, &_timeout_cookie);
_get_param_queue.return_front();
}
}
void MAVLinkParameters::reset_cache()
{
_cache.clear();
}
void MAVLinkParameters::process_param_value(const mavlink_message_t &message)
{
// LogDebug() << "getting param value";
mavlink_param_value_t param_value;
mavlink_msg_param_value_decode(&message, ¶m_value);
std::lock_guard<std::mutex> lock(_state_mutex);
if (_state == State::NONE) {
return;
}
if (_state == State::GET_PARAM_BUSY) {
auto work = _get_param_queue.borrow_front();
if (work) {
if (strncmp(work->param_name.c_str(), param_value.param_id, PARAM_ID_LEN) == 0) {
ParamValue value;
value.set_from_mavlink_param_value(param_value);
_cache[work->param_name] = value;
if (work->callback) {
work->callback(true, value);
}
_state = State::NONE;
_parent.unregister_timeout_handler(_timeout_cookie);
// LogDebug() << "time taken: " <<
// _parent.get_time().elapsed_since_s(_last_request_time);
_get_param_queue.pop_front();
} else {
// No match, let's just return the borrowed work item.
_get_param_queue.return_front();
}
}
}
else if (_state == State::SET_PARAM_BUSY) {
auto work = _set_param_queue.borrow_front();
if (work) {
// Now it still needs to match the param name
if (strncmp(work->param_name.c_str(), param_value.param_id, PARAM_ID_LEN) == 0) {
// We are done, inform caller and go back to idle
_cache[work->param_name] = work->param_value;
if (work->callback) {
work->callback(true);
}
_state = State::NONE;
_parent.unregister_timeout_handler(_timeout_cookie);
// LogDebug() << "time taken: " <<
// _parent.get_time().elapsed_since_s(_last_request_time);
_set_param_queue.pop_front();
} else {
_set_param_queue.return_front();
}
}
}
}
void MAVLinkParameters::process_param_ext_value(const mavlink_message_t &message)
{
// LogDebug() << "getting param ext value";
mavlink_param_ext_value_t param_ext_value;
mavlink_msg_param_ext_value_decode(&message, ¶m_ext_value);
std::lock_guard<std::mutex> lock(_state_mutex);
if (_state == State::NONE) {
return;
}
if (_state == State::GET_PARAM_BUSY) {
auto work = _get_param_queue.borrow_front();
if (work) {
if (strncmp(work->param_name.c_str(), param_ext_value.param_id, PARAM_ID_LEN) == 0) {
ParamValue value;
value.set_from_mavlink_param_ext_value(param_ext_value);
_cache[work->param_name] = value;
if (work->callback) {
work->callback(true, value);
}
_state = State::NONE;
_parent.unregister_timeout_handler(_timeout_cookie);
// LogDebug() << "time taken: " <<
// _parent.get_time().elapsed_since_s(_last_request_time);
_get_param_queue.pop_front();
} else {
_get_param_queue.return_front();
}
}
}
#if 0
else if (_state == State::SET_PARAM_BUSY) {
auto work = _set_param_queue.borrow_front();
if (work) {
// Now it still needs to match the param name
if (strncmp(work->param_name.c_str(), param_ext_value.param_id, PARAM_ID_LEN) == 0) {
// We are done, inform caller and go back to idle
_cache[work->param_name] = work->param_value;
if (work->callback) {
work->callback(true);
}
_state = State::NONE;
_parent.unregister_timeout_handler(_timeout_cookie);
// LogDebug() << "time taken: " << _parent.get_time().elapsed_since_s(_last_request_time);
_set_param_queue.pop_front();
} else {
_set_param_queue.return_front();
}
}
}
#endif
}
void MAVLinkParameters::process_param_ext_ack(const mavlink_message_t &message)
{
// LogDebug() << "getting param ext ack";
mavlink_param_ext_ack_t param_ext_ack;
mavlink_msg_param_ext_ack_decode(&message, ¶m_ext_ack);
std::lock_guard<std::mutex> lock(_state_mutex);
if (_state != State::SET_PARAM_BUSY) {
return;
}
auto work = _set_param_queue.borrow_front();
if (work) {
// Now it still needs to match the param name
if (strncmp(work->param_name.c_str(), param_ext_ack.param_id, PARAM_ID_LEN) == 0) {
if (param_ext_ack.param_result == PARAM_ACK_ACCEPTED) {
// We are done, inform caller and go back to idle
_cache[work->param_name] = work->param_value;
if (work->callback) {
work->callback(true);
}
_state = State::NONE;
_parent.unregister_timeout_handler(_timeout_cookie);
// LogDebug() << "time taken: " <<
// _parent.get_time().elapsed_since_s(_last_request_time);
_set_param_queue.pop_front();
} else if (param_ext_ack.param_result == PARAM_ACK_IN_PROGRESS) {
// Reset timeout and wait again.
_parent.refresh_timeout_handler(_timeout_cookie);
_set_param_queue.return_front();
} else {
LogErr() << "Somehow we did not get an ack, we got: "
<< int(param_ext_ack.param_result);
// We are done but unsuccessful
// TODO: we need better error feedback
if (work->callback) {
work->callback(false);
}
_state = State::NONE;
_parent.unregister_timeout_handler(_timeout_cookie);
// LogDebug() << "time taken: " <<
// _parent.get_time().elapsed_since_s(_last_request_time);
_set_param_queue.pop_front();
}
} else {
_set_param_queue.return_front();
}
}
}
void MAVLinkParameters::receive_timeout()
{
std::lock_guard<std::mutex> lock(_state_mutex);
if (_state == State::NONE) {
// Strange, a timeout even though we're not doing anything
return;
}
if (_state == State::GET_PARAM_BUSY) {
auto work = _get_param_queue.borrow_front();
if (work) {
if (work->callback) {
ParamValue empty_value;
// Notify about timeout
LogErr() << "Error: get param busy timeout: " << work->param_name;
// LogErr() << "Got it after: " <<
// _parent.get_time().elapsed_since_s(_last_request_time);
work->callback(false, empty_value);
}
_state = State::NONE;
_get_param_queue.pop_front();
}
}
else if (_state == State::SET_PARAM_BUSY) {
// This means work has been going on that we should try again
if (_set_param_queue.size() > 0) {
auto work = _set_param_queue.borrow_front();
if (work->callback) {
// Notify about timeout
LogErr() << "Error: set param busy timeout: " << work->param_name;
// LogErr() << "Got it after: " <<
// _parent.get_time().elapsed_since_s(_last_request_time);
work->callback(false);
}
_state = State::NONE;
_set_param_queue.pop_front();
}
}
}
std::ostream &operator<<(std::ostream &strm, const MAVLinkParameters::ParamValue &obj)
{
strm << obj.get_string();
return strm;
}
} // namespace dronecode_sdk