-
Notifications
You must be signed in to change notification settings - Fork 88
Expand file tree
/
Copy pathmavlink.cpp
More file actions
290 lines (273 loc) · 9.62 KB
/
mavlink.cpp
File metadata and controls
290 lines (273 loc) · 9.62 KB
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
/*
mavlink class for handling OpenDroneID messages
*/
#include <Arduino.h>
#include "log.hpp"
#include "mavlink.h"
#include "board_config.h"
#include "version.h"
#include "parameters.h"
#define SERIAL_BAUD 115200
static HardwareSerial *serial_ports[MAVLINK_COMM_NUM_BUFFERS];
#include <generated/mavlink_helpers.h>
mavlink_system_t mavlink_system = {0, MAV_COMP_ID_ODID_TXRX_1};
/*
send a buffer out a MAVLink channel
*/
void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
{
if (chan >= MAVLINK_COMM_NUM_BUFFERS || serial_ports[uint8_t(chan)] == nullptr) {
return;
}
auto &serial = *serial_ports[uint8_t(chan)];
serial.write(buf, len);
}
/*
abstraction for MAVLink on a serial port
*/
MAVLinkSerial::MAVLinkSerial(HardwareSerial &_serial, mavlink_channel_t _chan) :
serial(_serial),
chan(_chan)
{
serial_ports[uint8_t(_chan - MAVLINK_COMM_0)] = &serial;
}
void MAVLinkSerial::init(void)
{
// print banner at startup
serial.printf("ArduRemoteID version %u.%u %08x\n",
FW_VERSION_MAJOR, FW_VERSION_MINOR, GIT_VERSION);
mavlink_system.sysid = g.mavlink_sysid;
}
void MAVLinkSerial::update(void)
{
const uint32_t now_ms = millis();
if (mavlink_system.sysid != 0) {
update_send();
} else if (g.mavlink_sysid != 0) {
mavlink_system.sysid = g.mavlink_sysid;
} else if (now_ms - last_hb_warn_ms >= 2000) {
last_hb_warn_ms = millis();
serial.printf("Waiting for heartbeat\n");
}
update_receive();
if (param_request_last_ms != 0 && now_ms - param_request_last_ms > 50) {
param_request_last_ms = now_ms;
float value;
if (param_next->get_as_float(value)) {
mavlink_msg_param_value_send(chan,
param_next->name, value,
MAV_PARAM_TYPE_REAL32,
g.param_count_float(),
g.param_index_float(param_next));
}
param_next++;
if (param_next->ptype == Parameters::ParamType::NONE) {
param_next = nullptr;
param_request_last_ms = 0;
}
}
}
void MAVLinkSerial::update_send(void)
{
uint32_t now_ms = millis();
if (now_ms - last_hb_ms >= 1000) {
last_hb_ms = now_ms;
mavlink_msg_heartbeat_send(
chan,
MAV_TYPE_ODID,
MAV_AUTOPILOT_INVALID,
0,
0,
0);
// send arming status
arm_status_send();
}
}
void MAVLinkSerial::update_receive(void)
{
// receive new packets
mavlink_message_t msg;
mavlink_status_t status;
status.packet_rx_drop_count = 0;
const uint16_t nbytes = serial.available();
for (uint16_t i=0; i<nbytes; i++) {
const uint8_t c = (uint8_t)serial.read();
// Try to get a new message
if (mavlink_parse_char(chan, c, &msg, &status)) {
process_packet(status, msg);
}
}
}
/*
printf via MAVLink STATUSTEXT for debugging
*/
void MAVLinkSerial::mav_printf(uint8_t severity, const char *fmt, ...)
{
va_list arg_list;
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
va_start(arg_list, fmt);
vsnprintf(text, sizeof(text), fmt, arg_list);
va_end(arg_list);
mavlink_msg_statustext_send(chan,
severity,
text,
0, 0);
}
void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &msg)
{
const uint32_t now_ms = millis();
switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT: {
mavlink_heartbeat_t hb;
if (mavlink_system.sysid == 0) {
mavlink_msg_heartbeat_decode(&msg, &hb);
if (msg.sysid > 0 && hb.type != MAV_TYPE_GCS) {
mavlink_system.sysid = msg.sysid;
}
}
break;
}
case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
mavlink_msg_open_drone_id_location_decode(&msg, &location);
serial_log("MAVLink: got Location\n");
if (last_location_timestamp != location.timestamp) {
//only update the timestamp if we receive information with a different timestamp
last_location_ms = millis();
last_location_timestamp = location.timestamp;
}
last_location_ms = now_ms;
break;
}
case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: {
mavlink_open_drone_id_basic_id_t basic_id_tmp;
serial_log("MAVLink: got BasicID\n");
mavlink_msg_open_drone_id_basic_id_decode(&msg, &basic_id_tmp);
if ((strlen((const char*) basic_id_tmp.uas_id) > 0) && (basic_id_tmp.id_type > 0) && (basic_id_tmp.id_type <= MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID)) {
//only update if we receive valid data
basic_id = basic_id_tmp;
last_basic_id_ms = now_ms;
}
break;
}
case MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION: {
mavlink_msg_open_drone_id_authentication_decode(&msg, &authentication);
serial_log("MAVLink: got Auth\n");
break;
}
case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: {
mavlink_msg_open_drone_id_self_id_decode(&msg, &self_id);
serial_log("MAVLink: got SelfID\n");
last_self_id_ms = now_ms;
break;
}
case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
mavlink_msg_open_drone_id_system_decode(&msg, &system);
serial_log("MAVLink: got System\n");
if ((last_system_timestamp != system.timestamp) || (system.timestamp == 0)) {
//only update the timestamp if we receive information with a different timestamp
last_system_ms = millis();
last_system_timestamp = system.timestamp;
}
break;
}
case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: {
serial_log("MAVLink: got System update\n");
mavlink_open_drone_id_system_update_t pkt_system_update;
mavlink_msg_open_drone_id_system_update_decode(&msg, &pkt_system_update);
system.operator_latitude = pkt_system_update.operator_latitude;
system.operator_longitude = pkt_system_update.operator_longitude;
system.operator_altitude_geo = pkt_system_update.operator_altitude_geo;
system.timestamp = pkt_system_update.timestamp;
if (last_system_ms != 0) {
// we can only mark system as updated if we have the other
// information already
if ((last_system_timestamp != system.timestamp) || (pkt_system_update.timestamp == 0)) {
//only update the timestamp if we receive information with a different timestamp
last_system_ms = millis();
last_system_timestamp = pkt_system_update.timestamp;
}
last_system_ms = now_ms;
}
break;
}
case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
mavlink_msg_open_drone_id_operator_id_decode(&msg, &operator_id);
serial_log("MAVLink: got OperatorID\n");
last_operator_id_ms = now_ms;
break;
}
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
param_next = g.find_by_index_float(0);
param_request_last_ms = millis();
break;
};
case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
mavlink_param_request_read_t pkt;
mavlink_msg_param_request_read_decode(&msg, &pkt);
const Parameters::Param *p;
if (pkt.param_index < 0) {
p = g.find(pkt.param_id);
} else {
p = g.find_by_index_float(pkt.param_index);
}
float value;
if (!p || !p->get_as_float(value)) {
return;
}
if (p != nullptr && (p->flags & PARAM_FLAG_HIDDEN)) {
return;
}
mavlink_msg_param_value_send(chan,
p->name, value,
MAV_PARAM_TYPE_REAL32,
g.param_count_float(),
g.param_index_float(p));
break;
}
case MAVLINK_MSG_ID_PARAM_SET: {
mavlink_param_set_t pkt;
mavlink_msg_param_set_decode(&msg, &pkt);
auto *p = g.find(pkt.param_id);
float value;
if (pkt.param_type != MAV_PARAM_TYPE_REAL32 ||
!p || !p->get_as_float(value)) {
return;
}
p->get_as_float(value);
if (g.lock_level > 0 &&
(strcmp(p->name, "LOCK_LEVEL") != 0 ||
uint8_t(pkt.param_value) <= uint8_t(value))) {
// only param set allowed is to increase lock level
mav_printf(MAV_SEVERITY_ERROR, "Parameters locked");
} else {
p->set_as_float(pkt.param_value);
}
p->get_as_float(value);
mavlink_msg_param_value_send(chan,
p->name, value,
MAV_PARAM_TYPE_REAL32,
g.param_count_float(),
g.param_index_float(p));
break;
}
case MAVLINK_MSG_ID_SECURE_COMMAND:
case MAVLINK_MSG_ID_SECURE_COMMAND_REPLY: {
mavlink_secure_command_t pkt;
mavlink_msg_secure_command_decode(&msg, &pkt);
handle_secure_command(pkt);
break;
}
default:
// we don't care about other packets
break;
}
}
void MAVLinkSerial::arm_status_send(void)
{
const uint8_t status = parse_fail==nullptr?MAV_ODID_ARM_STATUS_GOOD_TO_ARM:MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC;
const char *reason = parse_fail==nullptr?"":parse_fail;
mavlink_msg_open_drone_id_arm_status_send(
chan,
status,
reason);
}