CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp
Views: 1798
1
/*
2
Copyright (C) 2020 Kraus Hamdani Aerospace Inc. All rights reserved.
3
4
This program is free software: you can redistribute it and/or modify
5
it under the terms of the GNU General Public License as published by
6
the Free Software Foundation, either version 3 of the License, or
7
(at your option) any later version.
8
9
This program is distributed in the hope that it will be useful,
10
but WITHOUT ANY WARRANTY; without even the implied warranty of
11
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12
GNU General Public License for more details.
13
14
You should have received a copy of the GNU General Public License
15
along with this program. If not, see <http://www.gnu.org/licenses/>.
16
*/
17
18
#include "AP_ADSB_Sagetech.h"
19
20
#if HAL_ADSB_SAGETECH_ENABLED
21
#include <GCS_MAVLink/GCS.h>
22
#include <AP_SerialManager/AP_SerialManager.h>
23
#include <AP_HAL/utility/sparse-endian.h>
24
#include <stdio.h>
25
#include <time.h>
26
#include <string.h>
27
#include <math.h>
28
29
#define SAGETECH_SCALER_LATLNG (1.0f/2.145767E-5f) // 180/(2^23)
30
#define SAGETECH_SCALER_KNOTS_TO_CMS ((KNOTS_TO_M_PER_SEC/0.125f) * 100.0f)
31
#define SAGETECH_SCALER_ALTITUDE (1.0f/0.015625f)
32
#define SAGETECH_SCALER_HEADING_CM ((360.0f/256.0f) * 100.0f)
33
34
#define SAGETECH_VALIDFLAG_LATLNG (1U<<0)
35
#define SAGETECH_VALIDFLAG_ALTITUDE (1U<<1)
36
#define SAGETECH_VALIDFLAG_VELOCITY (1U<<2)
37
#define SAGETECH_VALIDFLAG_GND_SPEED (1U<<3)
38
#define SAGETECH_VALIDFLAG_HEADING (1U<<4)
39
#define SAGETECH_VALIDFLAG_V_RATE_GEO (1U<<5)
40
#define SAGETECH_VALIDFLAG_V_RATE_BARO (1U<<6)
41
#define SAGETECH_VALIDFLAG_EST_LATLNG (1U<<7)
42
#define SAGETECH_VALIDFLAG_EST_VELOCITY (1U<<8)
43
44
// detect if any port is configured as Sagetech
45
bool AP_ADSB_Sagetech::detect()
46
{
47
return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_ADSB, 0);
48
}
49
50
// Init, called once after class is constructed
51
bool AP_ADSB_Sagetech::init()
52
{
53
_port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_ADSB, 0);
54
55
return (_port != nullptr);
56
}
57
58
void AP_ADSB_Sagetech::update()
59
{
60
if (_port == nullptr) {
61
return;
62
}
63
64
const uint32_t now_ms = AP_HAL::millis();
65
66
// -----------------------------
67
// read any available data on serial port
68
// -----------------------------
69
uint32_t nbytes = MIN(_port->available(), 10 * PAYLOAD_XP_MAX_SIZE);
70
while (nbytes-- > 0) {
71
uint8_t data;
72
if (!_port->read(data)) {
73
break;
74
}
75
if (parse_byte_XP(data)) {
76
handle_packet_XP(message_in.packet);
77
}
78
} // while nbytes
79
80
81
// -----------------------------
82
// handle timers for generating data
83
// -----------------------------
84
if (!last_packet_initialize_ms || (now_ms - last_packet_initialize_ms >= 5000)) {
85
last_packet_initialize_ms = now_ms;
86
send_packet(MsgType_XP::Installation_Set);
87
88
} else if (!last_packet_PreFlight_ms || (now_ms - last_packet_PreFlight_ms >= 8200)) {
89
last_packet_PreFlight_ms = now_ms;
90
// TODO: allow callsign to not require a reboot
91
send_packet(MsgType_XP::Preflight_Set);
92
93
} else if (now_ms - last_packet_Operating_ms >= 1000 && (
94
last_packet_Operating_ms == 0 || // send once at boot
95
// send as data changes
96
last_operating_squawk != _frontend.out_state.cfg.squawk_octal ||
97
abs(last_operating_alt - _frontend._my_loc.alt) > 1555 || // 1493cm == 49ft. The output resolution is 100ft per bit
98
last_operating_rf_select != _frontend.out_state.cfg.rfSelect))
99
{
100
last_packet_Operating_ms = now_ms;
101
last_operating_squawk = _frontend.out_state.cfg.squawk_octal;
102
last_operating_alt = _frontend._my_loc.alt;
103
last_operating_rf_select = _frontend.out_state.cfg.rfSelect;
104
send_packet(MsgType_XP::Operating_Set);
105
106
} else if (now_ms - last_packet_GPS_ms >= (_frontend.out_state.is_flying ? 200 : 1000)) {
107
// 1Hz when not flying, 5Hz when flying
108
last_packet_GPS_ms = now_ms;
109
send_packet(MsgType_XP::GPS_Set);
110
}
111
}
112
113
void AP_ADSB_Sagetech::send_packet(const MsgType_XP type)
114
{
115
switch (type) {
116
case MsgType_XP::Installation_Set:
117
send_msg_Installation();
118
break;
119
case MsgType_XP::Preflight_Set:
120
send_msg_PreFlight();
121
break;
122
case MsgType_XP::Operating_Set:
123
send_msg_Operating();
124
break;
125
case MsgType_XP::GPS_Set:
126
send_msg_GPS();
127
break;
128
default:
129
break;
130
}
131
}
132
133
void AP_ADSB_Sagetech::request_packet(const MsgType_XP type)
134
{
135
// set all bytes in packet to 0 via {} so we only need to set the ones we need to
136
Packet_XP pkt {};
137
138
pkt.type = MsgType_XP::Request;
139
pkt.id = 0;
140
pkt.payload_length = 4;
141
142
pkt.payload[0] = static_cast<uint8_t>(type);
143
144
send_msg(pkt);
145
}
146
147
148
void AP_ADSB_Sagetech::handle_packet_XP(const Packet_XP &msg)
149
{
150
switch (msg.type) {
151
case MsgType_XP::ACK:
152
handle_ack(msg);
153
break;
154
155
case MsgType_XP::Installation_Response:
156
case MsgType_XP::Preflight_Response:
157
case MsgType_XP::Status_Response:
158
// TODO add support for these
159
break;
160
161
case MsgType_XP::ADSB_StateVector_Report:
162
case MsgType_XP::ADSB_ModeStatus_Report:
163
case MsgType_XP::TISB_StateVector_Report:
164
case MsgType_XP::TISB_ModeStatus_Report:
165
case MsgType_XP::TISB_CorasePos_Report:
166
case MsgType_XP::TISB_ADSB_Mgr_Report:
167
handle_adsb_in_msg(msg);
168
break;
169
170
case MsgType_XP::Installation_Set:
171
case MsgType_XP::Preflight_Set:
172
case MsgType_XP::Operating_Set:
173
case MsgType_XP::GPS_Set:
174
case MsgType_XP::Request:
175
// these are out-bound only and are not expected to be received
176
case MsgType_XP::INVALID:
177
break;
178
}
179
}
180
181
void AP_ADSB_Sagetech::handle_ack(const Packet_XP &msg)
182
{
183
// ACK received!
184
const uint8_t system_state = msg.payload[2];
185
transponder_type = (Transponder_Type)msg.payload[6];
186
187
const uint8_t prev_transponder_mode = last_ack_transponder_mode;
188
last_ack_transponder_mode = (system_state >> 6) & 0x03;
189
if (prev_transponder_mode != last_ack_transponder_mode) {
190
static const char *mode_names[] = {"OFF", "STBY", "ON", "ON-ALT"};
191
if (last_ack_transponder_mode < ARRAY_SIZE(mode_names)) {
192
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: RF Mode: %s", mode_names[last_ack_transponder_mode]);
193
}
194
}
195
}
196
197
void AP_ADSB_Sagetech::handle_adsb_in_msg(const Packet_XP &msg)
198
{
199
AP_ADSB::adsb_vehicle_t vehicle {};
200
201
vehicle.last_update_ms = AP_HAL::millis();
202
203
switch (msg.type) {
204
case MsgType_XP::ADSB_StateVector_Report: { // 0x91
205
const uint16_t validFlags = le16toh_ptr(&msg.payload[8]);
206
vehicle.info.ICAO_address = le24toh_ptr(&msg.payload[10]);
207
208
if (validFlags & SAGETECH_VALIDFLAG_LATLNG) {
209
vehicle.info.lat = ((int32_t)le24toh_ptr(&msg.payload[20])) * SAGETECH_SCALER_LATLNG;
210
vehicle.info.lon = ((int32_t)le24toh_ptr(&msg.payload[23])) * SAGETECH_SCALER_LATLNG;
211
vehicle.info.flags |= ADSB_FLAGS_VALID_COORDS;
212
}
213
214
if (validFlags & SAGETECH_VALIDFLAG_ALTITUDE) {
215
vehicle.info.altitude = (int32_t)le24toh_ptr(&msg.payload[26]);
216
vehicle.info.flags |= ADSB_FLAGS_VALID_ALTITUDE;
217
}
218
219
if (validFlags & SAGETECH_VALIDFLAG_VELOCITY) {
220
const float velNS = ((int32_t)le16toh_ptr(&msg.payload[29])) * SAGETECH_SCALER_KNOTS_TO_CMS;
221
const float velEW = ((int32_t)le16toh_ptr(&msg.payload[31])) * SAGETECH_SCALER_KNOTS_TO_CMS;
222
vehicle.info.hor_velocity = Vector2f(velEW, velNS).length();
223
vehicle.info.flags |= ADSB_FLAGS_VALID_VELOCITY;
224
}
225
226
if (validFlags & SAGETECH_VALIDFLAG_HEADING) {
227
vehicle.info.heading = ((float)msg.payload[29]) * SAGETECH_SCALER_HEADING_CM;
228
vehicle.info.flags |= ADSB_FLAGS_VALID_HEADING;
229
}
230
231
if ((validFlags & SAGETECH_VALIDFLAG_V_RATE_GEO) || (validFlags & SAGETECH_VALIDFLAG_V_RATE_BARO)) {
232
vehicle.info.ver_velocity = (int16_t)le16toh_ptr(&msg.payload[38]);
233
vehicle.info.flags |= ADSB_FLAGS_VERTICAL_VELOCITY_VALID;
234
}
235
236
_frontend.handle_adsb_vehicle(vehicle);
237
break;
238
}
239
case MsgType_XP::ADSB_ModeStatus_Report: // 0x92
240
vehicle.info.ICAO_address = le24toh_ptr(&msg.payload[9]);
241
242
if (msg.payload[16] != 0) {
243
// if string is non-null, consider it valid
244
memcpy(&vehicle.info, &msg.payload[16], 8);
245
vehicle.info.flags |= ADSB_FLAGS_VALID_CALLSIGN;
246
}
247
248
_frontend.handle_adsb_vehicle(vehicle);
249
break;
250
case MsgType_XP::TISB_StateVector_Report:
251
case MsgType_XP::TISB_ModeStatus_Report:
252
case MsgType_XP::TISB_CorasePos_Report:
253
case MsgType_XP::TISB_ADSB_Mgr_Report:
254
// TODO
255
return;
256
257
default:
258
return;
259
}
260
261
}
262
263
// handling inbound byte and process it in the state machine
264
// return true when a full packet has been received
265
bool AP_ADSB_Sagetech::parse_byte_XP(const uint8_t data)
266
{
267
switch (message_in.state) {
268
default:
269
case ParseState::WaitingFor_Start:
270
if (data == 0xA5) {
271
message_in.state = ParseState::WaitingFor_AssmAddr;
272
}
273
break;
274
case ParseState::WaitingFor_AssmAddr:
275
message_in.state = (data == 0x01) ? ParseState::WaitingFor_MsgType : ParseState::WaitingFor_Start;
276
break;
277
case ParseState::WaitingFor_MsgType:
278
message_in.packet.type = static_cast<MsgType_XP>(data);
279
message_in.state = ParseState::WaitingFor_MsgId;
280
break;
281
case ParseState::WaitingFor_MsgId:
282
message_in.packet.id = data;
283
message_in.state = ParseState::WaitingFor_PayloadLen;
284
break;
285
case ParseState::WaitingFor_PayloadLen:
286
message_in.packet.payload_length = data;
287
message_in.index = 0;
288
message_in.state = (data == 0) ? ParseState::WaitingFor_ChecksumFletcher : ParseState::WaitingFor_PayloadContents;
289
break;
290
291
case ParseState::WaitingFor_PayloadContents:
292
message_in.packet.payload[message_in.index++] = data;
293
if (message_in.index >= message_in.packet.payload_length) {
294
message_in.state = ParseState::WaitingFor_ChecksumFletcher;
295
message_in.index = 0;
296
}
297
break;
298
299
case ParseState::WaitingFor_ChecksumFletcher:
300
message_in.packet.checksumFletcher = data;
301
message_in.state = ParseState::WaitingFor_Checksum;
302
break;
303
case ParseState::WaitingFor_Checksum:
304
message_in.packet.checksum = data;
305
message_in.state = ParseState::WaitingFor_End;
306
if (checksum_verify_XP(message_in.packet)) {
307
handle_packet_XP(message_in.packet);
308
}
309
break;
310
311
case ParseState::WaitingFor_End:
312
// we don't care if the end value matches
313
message_in.state = ParseState::WaitingFor_Start;
314
break;
315
}
316
return false;
317
}
318
319
// compute Sum and FletcherSum values into a single value
320
// returns uint16_t with MSByte as Sum and LSByte FletcherSum
321
uint16_t AP_ADSB_Sagetech::checksum_generate_XP(Packet_XP &msg) const
322
{
323
uint8_t sum = 0;
324
uint8_t sumFletcher = 0;
325
326
const uint8_t header_message_format[5] {
327
0xA5, // start
328
0x01, // assembly address
329
static_cast<uint8_t>(msg.type),
330
msg.id,
331
msg.payload_length
332
};
333
334
for (uint8_t i=0; i<5; i++) {
335
sum += header_message_format[i];
336
sumFletcher += sum;
337
}
338
for (uint8_t i=0; i<msg.payload_length; i++) {
339
sum += msg.payload[i];
340
sumFletcher += sum;
341
}
342
343
return UINT16_VALUE(sum, sumFletcher);
344
}
345
346
// computes checksum and returns true if it matches msg checksum
347
bool AP_ADSB_Sagetech::checksum_verify_XP(Packet_XP &msg) const
348
{
349
const uint16_t checksum = checksum_generate_XP(msg);
350
return (HIGHBYTE(checksum) == msg.checksum) && (LOWBYTE(checksum) == msg.checksumFletcher);
351
}
352
353
// computes checksum and assigns checksum values to msg
354
void AP_ADSB_Sagetech::checksum_assign_XP(Packet_XP &msg)
355
{
356
const uint16_t checksum = checksum_generate_XP(msg);
357
msg.checksum = HIGHBYTE(checksum);
358
msg.checksumFletcher = LOWBYTE(checksum);
359
}
360
361
// send message to serial port
362
void AP_ADSB_Sagetech::send_msg(Packet_XP &msg)
363
{
364
// generate and populate checksums.
365
checksum_assign_XP(msg);
366
367
const uint8_t message_format_header[5] {
368
0xA5, // start
369
0x01, // assembly address
370
static_cast<uint8_t>(msg.type),
371
msg.id,
372
msg.payload_length
373
};
374
const uint8_t message_format_tail[3] {
375
msg.checksumFletcher,
376
msg.checksum,
377
0x5A // end
378
};
379
380
if (_port != nullptr) {
381
_port->write(message_format_header, sizeof(message_format_header));
382
_port->write(msg.payload, msg.payload_length);
383
_port->write(message_format_tail, sizeof(message_format_tail));
384
}
385
}
386
387
void AP_ADSB_Sagetech::send_msg_Installation()
388
{
389
Packet_XP pkt {};
390
391
pkt.type = MsgType_XP::Installation_Set;
392
pkt.payload_length = 28; // 28== 0x1C
393
394
// Mode C = 3, Mode S = 0
395
pkt.id = (transponder_type == Transponder_Type::Mode_C) ? 3 : 0;
396
397
// // convert a decimal 123456 to 0x123456
398
// TODO: do a proper conversion. The param contains "131313" but what gets transmitted over the air is 0x200F1.
399
const uint32_t icao_hex = AP_ADSB::convert_base_to_decimal(16, _frontend.out_state.cfg.ICAO_id_param);
400
put_le24_ptr(&pkt.payload[0], icao_hex);
401
402
memcpy(&pkt.payload[3], &_frontend.out_state.cfg.callsign, 8);
403
404
pkt.payload[11] = 0; // airspeed MAX
405
406
pkt.payload[12] = 0; // COM Port 0 baud, fixed at 57600
407
pkt.payload[13] = 0; // COM Port 1 baud, fixed at 57600
408
pkt.payload[14] = 0; // COM Port 2 baud, fixed at 57600
409
410
pkt.payload[15] = 1; // GPS from COM port 0 (this port)
411
pkt.payload[16] = 1; // GPS Integrity
412
413
pkt.payload[17] = _frontend.out_state.cfg.emitterType / 8; // Emitter Set
414
pkt.payload[18] = _frontend.out_state.cfg.emitterType & 0x0F; // Emitter Type
415
416
pkt.payload[19] = _frontend.out_state.cfg.lengthWidth; // Aircraft Size
417
418
pkt.payload[20] = 0; // Altitude Encoder Offset
419
pkt.payload[21] = 0; // Altitude Encoder Offset
420
421
pkt.payload[22] = 0x07; // ADSB In Control, enable reading everything
422
pkt.payload[23] = 30; // ADSB In Report max length COM Port 0 (this one)
423
pkt.payload[24] = 0; // ADSB In Report max length COM Port 1
424
425
send_msg(pkt);
426
}
427
428
void AP_ADSB_Sagetech::send_msg_PreFlight()
429
{
430
Packet_XP pkt {};
431
432
pkt.type = MsgType_XP::Preflight_Set;
433
pkt.id = 0;
434
pkt.payload_length = 10;
435
436
memcpy(&pkt.payload[0], &_frontend.out_state.cfg.callsign, 8);
437
438
memset(&pkt.payload[8], 0, 2);
439
440
send_msg(pkt);
441
}
442
443
void AP_ADSB_Sagetech::send_msg_Operating()
444
{
445
Packet_XP pkt {};
446
447
pkt.type = MsgType_XP::Operating_Set;
448
pkt.id = 0;
449
pkt.payload_length = 8;
450
451
// squawk
452
// param is saved as native octal so we need convert back to
453
// decimal because Sagetech will convert it back to octal
454
const uint16_t squawk = AP_ADSB::convert_base_to_decimal(8, last_operating_squawk);
455
put_le16_ptr(&pkt.payload[0], squawk);
456
457
// altitude
458
if (_frontend.out_state.cfg.rf_capable & 0x01) {
459
const float alt_meters = last_operating_alt * 0.01f;
460
const int32_t alt_feet = (int32_t)(alt_meters * FEET_TO_METERS);
461
const int16_t alt_feet_adj = (alt_feet + 50) / 100; // 1 = 100 feet, 1 = 149 feet, 5 = 500 feet
462
put_le16_ptr(&pkt.payload[2], alt_feet_adj);
463
464
} else {
465
// use integrated altitude - recommend by sagetech
466
pkt.payload[2] = 0x80;
467
pkt.payload[3] = 0x00;
468
}
469
470
// RF mode
471
pkt.payload[4] = last_operating_rf_select;
472
send_msg(pkt);
473
}
474
475
void AP_ADSB_Sagetech::send_msg_GPS()
476
{
477
Packet_XP pkt {};
478
479
pkt.type = MsgType_XP::GPS_Set;
480
pkt.payload_length = 52;
481
pkt.id = 0;
482
483
const auto &loc = _frontend._my_loc;
484
485
const int32_t longitude = loc.lng;
486
const int32_t latitude = loc.lat;
487
488
// longitude and latitude
489
// NOTE: these MUST be done in double or else we get roundoff in the maths
490
const double lon_deg = longitude * (double)1.0e-7 * (longitude < 0 ? -1 : 1);
491
const double lon_minutes = (lon_deg - int(lon_deg)) * 60;
492
snprintf((char*)&pkt.payload[0], 12, "%03u%02u.%05u", (unsigned)lon_deg, (unsigned)lon_minutes, unsigned((lon_minutes - (int)lon_minutes) * 1.0E5));
493
494
const double lat_deg = latitude * (double)1.0e-7 * (latitude < 0 ? -1 : 1);
495
const double lat_minutes = (lat_deg - int(lat_deg)) * 60;
496
snprintf((char*)&pkt.payload[11], 11, "%02u%02u.%05u", (unsigned)lat_deg, (unsigned)lat_minutes, unsigned((lat_minutes - (int)lat_minutes) * 1.0E5));
497
498
// ground speed
499
const Vector2f speed = loc.groundspeed_vector();
500
float speed_knots = speed.length() * M_PER_SEC_TO_KNOTS;
501
snprintf((char*)&pkt.payload[21], 7, "%03u.%02u", (unsigned)speed_knots, unsigned((speed_knots - (int)speed_knots) * 1.0E2));
502
503
// heading
504
float heading = wrap_360(degrees(speed.angle()));
505
snprintf((char*)&pkt.payload[27], 10, "%03u.%04u", unsigned(heading), unsigned((heading - (int)heading) * 1.0E4));
506
507
// hemisphere
508
uint8_t hemisphere = 0;
509
hemisphere |= (latitude >= 0) ? 0x01 : 0; // isNorth
510
hemisphere |= (longitude >= 0) ? 0x02 : 0; // isEast
511
hemisphere |= (loc.status() < AP_GPS_FixType::FIX_2D) ? 0x80 : 0; // isInvalid
512
pkt.payload[35] = hemisphere;
513
514
// time
515
uint64_t time_usec = loc.epoch_from_rtc_us;
516
if (loc.have_epoch_from_rtc_us) {
517
// not completely accurate, our time includes leap seconds and time_t should be without
518
const time_t time_sec = time_usec / 1000000;
519
struct tm tmd {};
520
struct tm* tm = gmtime_r(&time_sec, &tmd);
521
522
// format time string
523
snprintf((char*)&pkt.payload[36], 11, "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6);
524
} else {
525
memset(&pkt.payload[36],' ', 10);
526
}
527
528
send_msg(pkt);
529
}
530
531
#endif // HAL_ADSB_SAGETECH_ENABLED
532
533
534