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/Tools/AP_Periph/adsb.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
/*
16
AP_Periph ADSB support. This is designed to talk to a Ping ADSB
17
module over the UART
18
*/
19
20
#include <AP_HAL/AP_HAL_Boards.h>
21
#include "AP_Periph.h"
22
23
#ifdef HAL_PERIPH_ENABLE_ADSB
24
25
#include <AP_SerialManager/AP_SerialManager.h>
26
#include <dronecan_msgs.h>
27
28
extern const AP_HAL::HAL &hal;
29
30
/*
31
init ADSB support
32
*/
33
void AP_Periph_FW::adsb_init(void)
34
{
35
if (g.adsb_baudrate > 0) {
36
auto *uart = hal.serial(g.adsb_port);
37
if (uart == nullptr) {
38
return;
39
}
40
uart->begin(AP_SerialManager::map_baudrate(g.adsb_baudrate), 256, 256);
41
}
42
}
43
44
/*
45
update ADSB subsystem
46
*/
47
void AP_Periph_FW::adsb_update(void)
48
{
49
if (g.adsb_baudrate <= 0) {
50
return;
51
}
52
53
auto *uart = hal.serial(g.adsb_port);
54
if (uart == nullptr) {
55
return;
56
}
57
58
// look for incoming MAVLink ADSB_VEHICLE packets
59
const uint16_t nbytes = uart->available();
60
for (uint16_t i=0; i<nbytes; i++) {
61
const uint8_t c = (uint8_t)uart->read();
62
63
// Try to get a new message
64
if (mavlink_frame_char_buffer(&adsb.msg, &adsb.status, c, &adsb.msg, &adsb.status) == MAVLINK_FRAMING_OK) {
65
if (adsb.msg.msgid == MAVLINK_MSG_ID_ADSB_VEHICLE) {
66
// decode and send as UAVCAN TrafficReport
67
static mavlink_adsb_vehicle_t msg;
68
mavlink_msg_adsb_vehicle_decode(&adsb.msg, &msg);
69
can_send_ADSB(msg);
70
}
71
}
72
}
73
74
/*
75
some ADSB devices need a heartbeat to get the system ID
76
*/
77
const uint32_t now_ms = AP_HAL::millis();
78
if (now_ms - adsb.last_heartbeat_ms >= 1000) {
79
adsb.last_heartbeat_ms = now_ms;
80
mavlink_heartbeat_t heartbeat {};
81
mavlink_message_t msg;
82
heartbeat.type = MAV_TYPE_GENERIC;
83
heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
84
auto len = mavlink_msg_heartbeat_encode_status(1,
85
MAV_COMP_ID_PERIPHERAL,
86
&adsb.status,
87
&msg, &heartbeat);
88
89
uart->write((uint8_t*)&msg.magic, len);
90
}
91
}
92
93
/*
94
map an ADSB_VEHICLE MAVLink message to a UAVCAN TrafficReport message
95
*/
96
void AP_Periph_FW::can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg)
97
{
98
ardupilot_equipment_trafficmonitor_TrafficReport pkt {};
99
pkt.timestamp.usec = 0;
100
pkt.icao_address = msg.ICAO_address;
101
pkt.tslc = msg.tslc;
102
pkt.latitude_deg_1e7 = msg.lat;
103
pkt.longitude_deg_1e7 = msg.lon;
104
pkt.alt_m = msg.altitude * 1e-3;
105
106
pkt.heading = radians(msg.heading * 1e-2);
107
108
pkt.velocity[0] = cosf(pkt.heading) * msg.hor_velocity * 1e-2;
109
pkt.velocity[1] = sinf(pkt.heading) * msg.hor_velocity * 1e-2;
110
pkt.velocity[2] = -msg.ver_velocity * 1e-2;
111
112
pkt.squawk = msg.squawk;
113
memcpy(pkt.callsign, msg.callsign, MIN(sizeof(msg.callsign),sizeof(pkt.callsign)));
114
if (msg.flags & 0x8000) {
115
pkt.source = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_SOURCE_ADSB_UAT;
116
} else {
117
pkt.source = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_SOURCE_ADSB;
118
}
119
120
pkt.traffic_type = msg.emitter_type;
121
122
if ((msg.flags & ADSB_FLAGS_VALID_ALTITUDE) != 0 && msg.altitude_type == 0) {
123
pkt.alt_type = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_PRESSURE_AMSL;
124
} else if ((msg.flags & ADSB_FLAGS_VALID_ALTITUDE) != 0 && msg.altitude_type == 1) {
125
pkt.alt_type = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_WGS84;
126
} else {
127
pkt.alt_type = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_ALT_UNKNOWN;
128
}
129
130
pkt.lat_lon_valid = (msg.flags & ADSB_FLAGS_VALID_COORDS) != 0;
131
pkt.heading_valid = (msg.flags & ADSB_FLAGS_VALID_HEADING) != 0;
132
pkt.velocity_valid = (msg.flags & ADSB_FLAGS_VALID_VELOCITY) != 0;
133
pkt.callsign_valid = (msg.flags & ADSB_FLAGS_VALID_CALLSIGN) != 0;
134
pkt.ident_valid = (msg.flags & ADSB_FLAGS_VALID_SQUAWK) != 0;
135
pkt.simulated_report = (msg.flags & ADSB_FLAGS_SIMULATED) != 0;
136
137
// these flags are not in common.xml
138
pkt.vertical_velocity_valid = (msg.flags & 0x0080) != 0;
139
pkt.baro_valid = (msg.flags & 0x0100) != 0;
140
141
uint8_t buffer[ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_MAX_SIZE];
142
uint16_t total_size = ardupilot_equipment_trafficmonitor_TrafficReport_encode(&pkt, buffer, !periph.canfdout());
143
144
canard_broadcast(ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_SIGNATURE,
145
ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ID,
146
CANARD_TRANSFER_PRIORITY_LOWEST,
147
&buffer[0],
148
total_size);
149
}
150
151
#endif // HAL_PERIPH_ENABLE_ADSB
152
153