Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/AP_Periph/adsb.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15AP_Periph ADSB support. This is designed to talk to a Ping ADSB16module over the UART17*/1819#include <AP_HAL/AP_HAL_Boards.h>20#include "AP_Periph.h"2122#ifdef HAL_PERIPH_ENABLE_ADSB2324#include <AP_SerialManager/AP_SerialManager.h>25#include <dronecan_msgs.h>2627extern const AP_HAL::HAL &hal;2829/*30init ADSB support31*/32void AP_Periph_FW::adsb_init(void)33{34if (g.adsb_baudrate > 0) {35auto *uart = hal.serial(g.adsb_port);36if (uart == nullptr) {37return;38}39uart->begin(AP_SerialManager::map_baudrate(g.adsb_baudrate), 256, 256);40}41}4243/*44update ADSB subsystem45*/46void AP_Periph_FW::adsb_update(void)47{48if (g.adsb_baudrate <= 0) {49return;50}5152auto *uart = hal.serial(g.adsb_port);53if (uart == nullptr) {54return;55}5657// look for incoming MAVLink ADSB_VEHICLE packets58const uint16_t nbytes = uart->available();59for (uint16_t i=0; i<nbytes; i++) {60const uint8_t c = (uint8_t)uart->read();6162// Try to get a new message63if (mavlink_frame_char_buffer(&adsb.msg, &adsb.status, c, &adsb.msg, &adsb.status) == MAVLINK_FRAMING_OK) {64if (adsb.msg.msgid == MAVLINK_MSG_ID_ADSB_VEHICLE) {65// decode and send as UAVCAN TrafficReport66static mavlink_adsb_vehicle_t msg;67mavlink_msg_adsb_vehicle_decode(&adsb.msg, &msg);68can_send_ADSB(msg);69}70}71}7273/*74some ADSB devices need a heartbeat to get the system ID75*/76const uint32_t now_ms = AP_HAL::millis();77if (now_ms - adsb.last_heartbeat_ms >= 1000) {78adsb.last_heartbeat_ms = now_ms;79mavlink_heartbeat_t heartbeat {};80mavlink_message_t msg;81heartbeat.type = MAV_TYPE_GENERIC;82heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA;83auto len = mavlink_msg_heartbeat_encode_status(1,84MAV_COMP_ID_PERIPHERAL,85&adsb.status,86&msg, &heartbeat);8788uart->write((uint8_t*)&msg.magic, len);89}90}9192/*93map an ADSB_VEHICLE MAVLink message to a UAVCAN TrafficReport message94*/95void AP_Periph_FW::can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg)96{97ardupilot_equipment_trafficmonitor_TrafficReport pkt {};98pkt.timestamp.usec = 0;99pkt.icao_address = msg.ICAO_address;100pkt.tslc = msg.tslc;101pkt.latitude_deg_1e7 = msg.lat;102pkt.longitude_deg_1e7 = msg.lon;103pkt.alt_m = msg.altitude * 1e-3;104105pkt.heading = radians(msg.heading * 1e-2);106107pkt.velocity[0] = cosf(pkt.heading) * msg.hor_velocity * 1e-2;108pkt.velocity[1] = sinf(pkt.heading) * msg.hor_velocity * 1e-2;109pkt.velocity[2] = -msg.ver_velocity * 1e-2;110111pkt.squawk = msg.squawk;112memcpy(pkt.callsign, msg.callsign, MIN(sizeof(msg.callsign),sizeof(pkt.callsign)));113if (msg.flags & 0x8000) {114pkt.source = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_SOURCE_ADSB_UAT;115} else {116pkt.source = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_SOURCE_ADSB;117}118119pkt.traffic_type = msg.emitter_type;120121if ((msg.flags & ADSB_FLAGS_VALID_ALTITUDE) != 0 && msg.altitude_type == 0) {122pkt.alt_type = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_PRESSURE_AMSL;123} else if ((msg.flags & ADSB_FLAGS_VALID_ALTITUDE) != 0 && msg.altitude_type == 1) {124pkt.alt_type = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_WGS84;125} else {126pkt.alt_type = ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_ALT_UNKNOWN;127}128129pkt.lat_lon_valid = (msg.flags & ADSB_FLAGS_VALID_COORDS) != 0;130pkt.heading_valid = (msg.flags & ADSB_FLAGS_VALID_HEADING) != 0;131pkt.velocity_valid = (msg.flags & ADSB_FLAGS_VALID_VELOCITY) != 0;132pkt.callsign_valid = (msg.flags & ADSB_FLAGS_VALID_CALLSIGN) != 0;133pkt.ident_valid = (msg.flags & ADSB_FLAGS_VALID_SQUAWK) != 0;134pkt.simulated_report = (msg.flags & ADSB_FLAGS_SIMULATED) != 0;135136// these flags are not in common.xml137pkt.vertical_velocity_valid = (msg.flags & 0x0080) != 0;138pkt.baro_valid = (msg.flags & 0x0100) != 0;139140uint8_t buffer[ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_MAX_SIZE];141uint16_t total_size = ardupilot_equipment_trafficmonitor_TrafficReport_encode(&pkt, buffer, !periph.canfdout());142143canard_broadcast(ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_SIGNATURE,144ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ID,145CANARD_TRANSFER_PRIORITY_LOWEST,146&buffer[0],147total_size);148}149150#endif // HAL_PERIPH_ENABLE_ADSB151152153