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/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.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*/1415#include "AP_ADSB_uAvionix_MAVLink.h"1617#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED18#include <stdio.h> // for sprintf19#include <limits.h>20#include <GCS_MAVLink/GCS.h>2122#define ADSB_CHAN_TIMEOUT_MS 15000232425extern const AP_HAL::HAL& hal;2627// detect if an port is configured as MAVLink28bool AP_ADSB_uAvionix_MAVLink::detect()29{30// this actually requires SerialProtocol_MAVLink or SerialProtocol_MAVLink2 but31// we can't have a running system with that, so its safe to assume it's already defined32return true;33}3435void AP_ADSB_uAvionix_MAVLink::update()36{37const uint32_t now = AP_HAL::millis();3839// send static configuration data to transceiver, every 5s40if (_frontend.out_state.chan_last_ms > 0 && now - _frontend.out_state.chan_last_ms > ADSB_CHAN_TIMEOUT_MS) {41// haven't gotten a heartbeat health status packet in a while, assume hardware failure42_frontend.out_state.chan = -1;43_frontend.out_state.chan_last_ms = 0; // if the time isn't reset we spam the message44GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "ADSB: Transceiver heartbeat timed out");45} else if (_frontend.out_state.chan >= 0 && !_frontend._my_loc.is_zero() && _frontend.out_state.chan < MAVLINK_COMM_NUM_BUFFERS) {46const mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0 + _frontend.out_state.chan);47if (now - _frontend.out_state.last_config_ms >= 5000 && HAVE_PAYLOAD_SPACE(chan, UAVIONIX_ADSB_OUT_CFG)) {48_frontend.out_state.last_config_ms = now;49send_configure(chan);50} // last_config_ms5152// send dynamic data to transceiver at 5Hz53if (now - _frontend.out_state.last_report_ms >= 200 && HAVE_PAYLOAD_SPACE(chan, UAVIONIX_ADSB_OUT_DYNAMIC)) {54_frontend.out_state.last_report_ms = now;55send_dynamic_out(chan);56} // last_report_ms57} // chan_last_ms58}5960void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) const61{62const auto &_my_loc = _frontend._my_loc;63const auto &gps = _my_loc; // avoid churn6465const Vector3f &gps_velocity = gps.velocity();6667const int32_t latitude = _frontend._my_loc.lat;68const int32_t longitude = _frontend._my_loc.lng;69const int32_t altGNSS = _frontend._my_loc.alt * 10; // convert cm to mm70const int16_t velVert = -1.0f * gps_velocity.z * 1E2; // convert m/s to cm/s71const int16_t nsVog = gps_velocity.x * 1E2; // convert m/s to cm/s72const int16_t ewVog = gps_velocity.y * 1E2; // convert m/s to cm/s73const AP_GPS_FixType fixType = gps.status(); // this lines up perfectly with our enum74const uint8_t emStatus = 0; // TODO: implement this ENUM. no emergency = 075const uint8_t numSats = gps.num_sats();76const uint16_t squawk = _frontend.out_state.cfg.squawk_octal;7778uint32_t accHoriz = UINT_MAX;79float accHoriz_f;80if (gps.horizontal_accuracy(accHoriz_f)) {81accHoriz = accHoriz_f * 1E3; // convert m to mm82}8384uint16_t accVert = USHRT_MAX;85float accVert_f;86if (gps.vertical_accuracy(accVert_f)) {87accVert = accVert_f * 1E2; // convert m to cm88}8990uint16_t accVel = USHRT_MAX;91float accVel_f;92if (gps.speed_accuracy(accVel_f)) {93accVel = accVel_f * 1E3; // convert m/s to mm/s94}9596uint16_t state = 0;97if (_frontend.out_state.is_in_auto_mode) {98state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED;99}100if (!_frontend.out_state.is_flying) {101state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND;102}103104// TODO: confirm this sets utcTime correctly105const uint64_t gps_time = gps.time_epoch_usec();106const uint32_t utcTime = gps_time / 1000000ULL;107108int32_t altPres = INT_MAX;109if (_my_loc.baro_is_healthy) {110// Altitude difference between sea level pressure and current pressure. Result in millimeters111altPres = _my_loc.baro_alt_press_diff_sea_level * 1E3; // convert m to mm;112}113114115116mavlink_msg_uavionix_adsb_out_dynamic_send(117chan,118utcTime,119latitude,120longitude,121altGNSS,122uint8_t(fixType),123numSats,124altPres,125accHoriz,126accVert,127accVel,128velVert,129nsVog,130ewVog,131emStatus,132state,133squawk);134}135136137/*138* To expand functionality in their HW, uAvionix has extended a few of the unused MAVLink bits to pack in more new features139* This function will override the MSB byte of the 24bit ICAO address. To ensure an invalid >24bit ICAO is never broadcasted,140* this function is used to create the encoded version without ever writing to the actual ICAO number. It's created on-demand141*/142uint32_t AP_ADSB_uAvionix_MAVLink::encode_icao(const uint32_t icao_id) const143{144// utilize the upper unused 8bits of the icao with special flags.145// This encoding is required for uAvionix devices that break the MAVLink spec.146147// ensure the user assignable icao is 24 bits148uint32_t encoded_icao = icao_id & 0x00FFFFFF;149150encoded_icao &= ~0x20000000; // useGnssAltitude should always be FALSE151encoded_icao |= 0x10000000; // csidLogic should always be TRUE152153//SIL/SDA are special fields that should be set to 0 with only expert user adjustment154encoded_icao &= ~0x03000000; // SDA should always be FALSE155encoded_icao &= ~0x0C000000; // SIL should always be FALSE156157return encoded_icao;158}159160/*161* To expand functionality in their HW, uAvionix has extended a few of the unused MAVLink bits to pack in more new features162* This function will override the usually-null ending char of the callsign. It always encodes the last byte [8], even if163* the callsign string is less than 9 chars and there are other zero-padded nulls.164*/165uint8_t AP_ADSB_uAvionix_MAVLink::get_encoded_callsign_null_char()166{167// Encoding of the 8bit null char168// (LSB) - knots169// bit.1 - knots170// bit.2 - knots171// bit.3 - (unused)172// bit.4 - flag - ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN173// bit.5 - flag - ADSB_BITBASK_RF_CAPABILITIES_UAT_IN174// bit.6 - flag - 0 = callsign is treated as callsign, 1 = callsign is treated as flightPlanID/Squawk175// (MSB) - (unused)176177uint8_t encoded_null = 0;178179encoded_null = AP_ADSB::convert_maxknots_to_enum(_frontend.out_state.cfg.maxAircraftSpeed_knots);180181if (_frontend.out_state.cfg.rf_capable & ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN) {182encoded_null |= 0x10;183}184if (_frontend.out_state.cfg.rf_capable & ADSB_BITBASK_RF_CAPABILITIES_UAT_IN) {185encoded_null |= 0x20;186}187188189/*190If the user has an 8 digit flightPlanID assigned from a filed flight plan, this should be assigned to FlightPlanID, (assigned by remote app)191else if the user has an assigned squawk code from ATC this should be converted from 4 digit octal to 4 character alpha string and assigned to FlightPlanID,192else if a tail number is known it should be set to the tail number of the aircraft, (assigned by remote app)193else it should be left blank (all 0's)194*/195196// using the above logic, we must always assign the squawk. once we get configured197// externally then get_encoded_callsign_null_char() stops getting called198snprintf(_frontend.out_state.cfg.callsign, 5, "%04d", unsigned(_frontend.out_state.cfg.squawk_octal) & 0x1FFF);199memset(&_frontend.out_state.cfg.callsign[4], 0, 5); // clear remaining 5 chars200encoded_null |= 0x40;201202return encoded_null;203}204205/*206* populate and send MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG207*/208void AP_ADSB_uAvionix_MAVLink::send_configure(const mavlink_channel_t chan)209{210// MAVLink spec says the 9 byte callsign field is 8 byte string with 9th byte as null.211// Here we temporarily set some flags in that null char to signify the callsign212// may be a flightplanID instead213int8_t callsign[sizeof(_frontend.out_state.cfg.callsign)];214uint32_t icao;215216memcpy(callsign, _frontend.out_state.cfg.callsign, sizeof(_frontend.out_state.cfg.callsign));217218if (_frontend.out_state.cfg.was_set_externally) {219// take values as-is220icao = _frontend.out_state.cfg.ICAO_id;221} else {222callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = (int8_t)get_encoded_callsign_null_char();223icao = encode_icao((uint32_t)_frontend.out_state.cfg.ICAO_id);224}225226mavlink_msg_uavionix_adsb_out_cfg_send(227chan,228icao,229(const char*)callsign,230(uint8_t)_frontend.out_state.cfg.emitterType,231(uint8_t)_frontend.out_state.cfg.lengthWidth,232(uint8_t)_frontend.out_state.cfg.gpsOffsetLat,233(uint8_t)_frontend.out_state.cfg.gpsOffsetLon,234_frontend.out_state.cfg.stall_speed_cm,235(uint8_t)_frontend.out_state.cfg.rfSelect);236}237238#endif // HAL_ADSB_UAVIONIX_MAVLINK_ENABLED239240241