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_Frsky_Telem/AP_Frsky_SPort.cpp
Views: 1798
#include "AP_Frsky_SPort.h"12#if AP_FRSKY_SPORT_TELEM_ENABLED34#include <AP_HAL/utility/sparse-endian.h>5#include <AP_BattMonitor/AP_BattMonitor.h>6#include <AP_GPS/AP_GPS.h>7#include <GCS_MAVLink/GCS.h>8#include <AP_RPM/AP_RPM.h>910#include "AP_Frsky_SPortParser.h"1112#include <string.h>1314extern const AP_HAL::HAL& hal;1516AP_Frsky_SPort *AP_Frsky_SPort::singleton;1718/*19* send telemetry data20* for FrSky SPort protocol (X-receivers)21*/22void AP_Frsky_SPort::send(void)23{24const uint16_t numc = MIN(_port->available(), 1024U);2526// this is the constant for hub data frame27if (_port->txspace() < 19) {28return;29}3031if (numc == 0) {32// no serial data to process do bg tasks33if (_SPort.vario_refresh) {34calc_nav_alt(); // nav altitude is not recalculated until all of it has been sent35_SPort.vario_refresh = false;36}37if (_SPort.gps_refresh) {38calc_gps_position(); // gps data is not recalculated until all of it has been sent39_SPort.gps_refresh = false;40}41return;42}4344for (int16_t i = 0; i < numc; i++) {45uint8_t readbyte;46if (!_port->read(readbyte)) {47break;48}49if (_SPort.sport_status == false) {50if (readbyte == FRAME_HEAD) {51_SPort.sport_status = true;52}53} else {54const AP_BattMonitor &_battery = AP::battery();55switch (readbyte) {56case SENSOR_ID_VARIO: // Sensor ID 057switch (_SPort.vario_call) {58case 0:59send_sport_frame(SPORT_DATA_FRAME, ALT_ID, _SPort_data.alt_nav_meters*100 + _SPort_data.alt_nav_cm); // send altitude in cm60break;61case 1:62send_sport_frame(SPORT_DATA_FRAME, VARIO_ID, _SPort_data.vario_vspd); // send vspeed cm/s63_SPort.vario_refresh = true;64break;65}66if (++_SPort.vario_call > 1) {67_SPort.vario_call = 0;68}69break;70case SENSOR_ID_FAS: // Sensor ID 271switch (_SPort.fas_call) {72case 0:73{74uint8_t percentage = 0;75IGNORE_RETURN(_battery.capacity_remaining_pct(percentage));76send_sport_frame(SPORT_DATA_FRAME, FUEL_ID, (uint16_t)roundf(percentage)); // send battery remaining77break;78}79case 1:80send_sport_frame(SPORT_DATA_FRAME, VFAS_ID, (uint16_t)roundf(_battery.voltage() * 100.0f)); // send battery voltage in cV81break;82case 2: {83float current;84if (!_battery.current_amps(current)) {85current = 0;86}87send_sport_frame(SPORT_DATA_FRAME, CURR_ID, (uint16_t)roundf(current * 10.0f)); // send current consumption in dA88break;89}90break;91}92if (++_SPort.fas_call > 2) {93_SPort.fas_call = 0;94}95break;96case SENSOR_ID_GPS: // Sensor ID 397switch (_SPort.gps_call) {98case 0:99send_sport_frame(SPORT_DATA_FRAME, GPS_LONG_LATI_FIRST_ID, calc_gps_latlng(_passthrough.send_latitude)); // gps latitude or longitude100break;101case 1:102send_sport_frame(SPORT_DATA_FRAME, GPS_LONG_LATI_FIRST_ID, calc_gps_latlng(_passthrough.send_latitude)); // gps latitude or longitude103break;104case 2:105send_sport_frame(SPORT_DATA_FRAME, GPS_SPEED_ID, _SPort_data.speed_in_meter*1000 + _SPort_data.speed_in_centimeter*10); // send gps speed in mm/sec106break;107case 3:108send_sport_frame(SPORT_DATA_FRAME, GPS_ALT_ID, _SPort_data.alt_gps_meters*100+_SPort_data.alt_gps_cm); // send gps altitude in cm109break;110case 4:111send_sport_frame(SPORT_DATA_FRAME, GPS_COURS_ID, _SPort_data.yaw*100); // send heading in cd based on AHRS and not GPS112_SPort.gps_refresh = true;113break;114}115if (++_SPort.gps_call > 4) {116_SPort.gps_call = 0;117}118break;119case SENSOR_ID_RPM: // Sensor ID 4120#if AP_RPM_ENABLED121{122const AP_RPM* rpm = AP::rpm();123if (rpm == nullptr) {124break;125}126int32_t value;127if (calc_rpm(_SPort.rpm_call, value)) {128// use high numbered frsky sensor ids to leave low numbered free for externally attached physical frsky sensors129uint16_t id = RPM1_ID;130if (_SPort.rpm_call != 0) {131// only two sensors are currently supported132id = RPM2_ID;133}134send_sport_frame(SPORT_DATA_FRAME, id, value);135}136if (++_SPort.rpm_call > MIN(rpm->num_sensors()-1, 1)) {137_SPort.rpm_call = 0;138}139}140#endif // AP_RPM_ENABLED141break;142case SENSOR_ID_SP2UR: // Sensor ID 6143switch (_SPort.various_call) {144case 0 :145send_sport_frame(SPORT_DATA_FRAME, TEMP2_ID, (uint16_t)(AP::gps().num_sats() * 10 + AP::gps().status())); // send GPS status and number of satellites as num_sats*10 + status (to fit into a uint8_t)146break;147case 1:148send_sport_frame(SPORT_DATA_FRAME, TEMP1_ID, gcs().custom_mode()); // send flight mode149break;150}151if (++_SPort.various_call > 1) {152_SPort.various_call = 0;153}154break;155default:156{157// respond to custom user data polling158WITH_SEMAPHORE(_sport_push_buffer.sem);159if (_sport_push_buffer.pending && readbyte == _sport_push_buffer.packet.sensor) {160send_sport_frame(_sport_push_buffer.packet.frame, _sport_push_buffer.packet.appid, _sport_push_buffer.packet.data);161_sport_push_buffer.pending = false;162}163}164break;165}166_SPort.sport_status = false;167}168}169}170171/*172* prepare gps latitude/longitude data173* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)174*/175uint32_t AP_Frsky_SPort::calc_gps_latlng(bool &send_latitude)176{177const Location &loc = AP::gps().location(0); // use the first gps instance (same as in send_mavlink_gps_raw)178179// alternate between latitude and longitude180if (send_latitude == true) {181send_latitude = false;182if (loc.lat < 0) {183return ((labs(loc.lat)/100)*6) | 0x40000000;184} else {185return ((labs(loc.lat)/100)*6);186}187} else {188send_latitude = true;189if (loc.lng < 0) {190return ((labs(loc.lng)/100)*6) | 0xC0000000;191} else {192return ((labs(loc.lng)/100)*6) | 0x80000000;193}194}195}196197/*198* send an 8 bytes SPort frame of FrSky data - for FrSky SPort protocol (X-receivers)199*/200void AP_Frsky_SPort::send_sport_frame(uint8_t frame, uint16_t appid, uint32_t data)201{202uint8_t buf[8];203204buf[0] = frame;205buf[1] = appid & 0xFF;206buf[2] = appid >> 8;207memcpy(&buf[3], &data, 4);208209uint16_t sum = 0;210for (uint8_t i=0; i<sizeof(buf)-1; i++) {211sum += buf[i];212sum += sum >> 8;213sum &= 0xFF;214}215sum = 0xff - ((sum & 0xff) + (sum >> 8));216buf[7] = (uint8_t)sum;217218// perform byte stuffing per SPort spec219uint8_t len = 0;220uint8_t buf2[sizeof(buf)*2+1];221222for (uint8_t i=0; i<sizeof(buf); i++) {223uint8_t c = buf[i];224if (c == FRAME_DLE || buf[i] == FRAME_HEAD) {225buf2[len++] = FRAME_DLE;226buf2[len++] = c ^ FRAME_XOR;227} else {228buf2[len++] = c;229}230}231#ifndef HAL_BOARD_SITL232/*233check that we haven't been too slow in responding to the new234UART data. If we respond too late then we will overwrite the next235polling frame.236SPort poll-to-poll period is 11.65ms, a frame takes 1.38ms237but specs require we release the bus before 8ms leaving us with 6500us238*/239const uint64_t tend_us = port->receive_time_constraint_us(1);240const uint64_t now_us = AP_HAL::micros64();241const uint64_t tdelay_us = now_us - tend_us;242if (tdelay_us > 6500) {243// we've been too slow in responding244return;245}246#endif247_port->write(buf2, len);248}249250extern const AP_HAL::HAL& hal;251252bool AP_Frsky_SPortParser::should_process_packet(const uint8_t *packet, bool discard_duplicates)253{254// check for duplicate packets255if (discard_duplicates) {256/*257Note: the polling byte packet[0] should be ignored in the comparison258because we might get the same packet with different polling bytes259We have 2 types of duplicate packets: ghost identical packets sent by the receiver260and user duplicate packets sent to compensate for bad link and frame loss, this261check should address both types.262*/263if (memcmp(&packet[1], &_parse_state.last_packet[1], SPORT_PACKET_SIZE-1) == 0) {264return false;265}266memcpy(_parse_state.last_packet, packet, SPORT_PACKET_SIZE);267}268//check CRC269int16_t crc = 0;270for (uint8_t i=1; i<SPORT_PACKET_SIZE; ++i) {271crc += _parse_state.rx_buffer[i]; // 0-1FE272crc += crc >> 8; // 0-1FF273crc &= 0x00ff; // 0-FF274}275return (crc == 0x00ff);276}277278bool AP_Frsky_SPortParser::process_byte(AP_Frsky_SPort::sport_packet_t &sport_packet, const uint8_t data)279{280switch (_parse_state.state) {281case ParseState::START:282if (_parse_state.rx_buffer_count < TELEMETRY_RX_BUFFER_SIZE) {283_parse_state.rx_buffer[_parse_state.rx_buffer_count++] = data;284}285_parse_state.state = ParseState::IN_FRAME;286break;287288case ParseState::IN_FRAME:289if (data == FRAME_DLE) {290_parse_state.state = ParseState::XOR; // XOR next byte291} else if (data == FRAME_HEAD) {292_parse_state.state = ParseState::IN_FRAME ;293_parse_state.rx_buffer_count = 0;294break;295} else if (_parse_state.rx_buffer_count < TELEMETRY_RX_BUFFER_SIZE) {296_parse_state.rx_buffer[_parse_state.rx_buffer_count++] = data;297}298break;299300case ParseState::XOR:301if (_parse_state.rx_buffer_count < TELEMETRY_RX_BUFFER_SIZE) {302_parse_state.rx_buffer[_parse_state.rx_buffer_count++] = data ^ STUFF_MASK;303}304_parse_state.state = ParseState::IN_FRAME;305break;306307case ParseState::IDLE:308if (data == FRAME_HEAD) {309_parse_state.rx_buffer_count = 0;310_parse_state.state = ParseState::START;311}312break;313314} // switch315316if (_parse_state.rx_buffer_count >= SPORT_PACKET_SIZE) {317_parse_state.rx_buffer_count = 0;318_parse_state.state = ParseState::IDLE;319// feed the packet only if it's not a duplicate320return get_packet(sport_packet, true);321}322return false;323}324325bool AP_Frsky_SPortParser::get_packet(AP_Frsky_SPort::sport_packet_t &sport_packet, bool discard_duplicates)326{327if (!should_process_packet(_parse_state.rx_buffer, discard_duplicates)) {328return false;329}330331const AP_Frsky_SPort::sport_packet_t sp {332{ _parse_state.rx_buffer[0],333_parse_state.rx_buffer[1],334le16toh_ptr(&_parse_state.rx_buffer[2]),335le32toh_ptr(&_parse_state.rx_buffer[4]) },336};337338sport_packet = sp;339return true;340}341342/*343* Calculates the sensor id from the physical sensor index [0-27]3440x00, // Physical ID 0 - Vario2 (altimeter high precision)3450xA1, // Physical ID 1 - FLVSS Lipo sensor3460x22, // Physical ID 2 - FAS-40S current sensor3470x83, // Physical ID 3 - GPS / altimeter (normal precision)3480xE4, // Physical ID 4 - RPM3490x45, // Physical ID 5 - SP2UART(Host)3500xC6, // Physical ID 6 - SPUART(Remote)3510x67, // Physical ID 7 - Ardupilot/Betaflight EXTRA DOWNLINK3520x48, // Physical ID 8 -3530xE9, // Physical ID 9 -3540x6A, // Physical ID 10 -3550xCB, // Physical ID 11 -3560xAC, // Physical ID 12 -3570x0D, // Physical ID 13 - Ardupilot/Betaflight UPLINK3580x8E, // Physical ID 14 -3590x2F, // Physical ID 15 -3600xD0, // Physical ID 16 -3610x71, // Physical ID 17 -3620xF2, // Physical ID 18 -3630x53, // Physical ID 19 -3640x34, // Physical ID 20 - Ardupilot/Betaflight EXTRA DOWNLINK3650x95, // Physical ID 21 -3660x16, // Physical ID 22 - GAS Suite3670xB7, // Physical ID 23 - IMU ACC (x,y,z)3680x98, // Physical ID 24 -3690x39, // Physical ID 25 - Power Box3700xBA // Physical ID 26 - Temp3710x1B // Physical ID 27 - ArduPilot/Betaflight DEFAULT DOWNLINK372* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)373*/374#undef BIT375#define BIT(x, index) (((x) >> index) & 0x01)376uint8_t AP_Frsky_SPort::calc_sensor_id(const uint8_t physical_id)377{378uint8_t result = physical_id;379result += (BIT(physical_id, 0) ^ BIT(physical_id, 1) ^ BIT(physical_id, 2)) << 5;380result += (BIT(physical_id, 2) ^ BIT(physical_id, 3) ^ BIT(physical_id, 4)) << 6;381result += (BIT(physical_id, 0) ^ BIT(physical_id, 2) ^ BIT(physical_id, 4)) << 7;382return result;383}384385/*386* prepare value for transmission through FrSky link387* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)388*/389uint16_t AP_Frsky_SPort::prep_number(int32_t number, uint8_t digits, uint8_t power)390{391uint16_t res = 0;392uint32_t abs_number = abs(number);393394if ((digits == 2) && (power == 0)) { // number encoded on 7 bits, client side needs to know if expected range is 0,127 or -63,63395uint8_t max_value = number < 0 ? (0x1<<6)-1 : (0x1<<7)-1;396res = constrain_int16(abs_number,0,max_value);397if (number < 0) { // if number is negative, add sign bit in front398res |= 1U<<6;399}400} else if ((digits == 2) && (power == 1)) { // number encoded on 8 bits: 7 bits for digits + 1 for 10^power401if (abs_number < 100) {402res = abs_number<<1;403} else if (abs_number < 1270) {404res = ((uint8_t)roundf(abs_number * 0.1f)<<1)|0x1;405} else { // transmit max possible value (0x7F x 10^1 = 1270)406res = 0xFF;407}408if (number < 0) { // if number is negative, add sign bit in front409res |= 0x1<<8;410}411} else if ((digits == 2) && (power == 2)) { // number encoded on 9 bits: 7 bits for digits + 2 for 10^power412if (abs_number < 100) {413res = abs_number<<2;414} else if (abs_number < 1000) {415res = ((uint8_t)roundf(abs_number * 0.1f)<<2)|0x1;416} else if (abs_number < 10000) {417res = ((uint8_t)roundf(abs_number * 0.01f)<<2)|0x2;418} else if (abs_number < 127000) {419res = ((uint8_t)roundf(abs_number * 0.001f)<<2)|0x3;420} else { // transmit max possible value (0x7F x 10^3 = 127000)421res = 0x1FF;422}423if (number < 0) { // if number is negative, add sign bit in front424res |= 0x1<<9;425}426} else if ((digits == 3) && (power == 1)) { // number encoded on 11 bits: 10 bits for digits + 1 for 10^power427if (abs_number < 1000) {428res = abs_number<<1;429} else if (abs_number < 10240) {430res = ((uint16_t)roundf(abs_number * 0.1f)<<1)|0x1;431} else { // transmit max possible value (0x3FF x 10^1 = 10230)432res = 0x7FF;433}434if (number < 0) { // if number is negative, add sign bit in front435res |= 0x1<<11;436}437} else if ((digits == 3) && (power == 2)) { // number encoded on 12 bits: 10 bits for digits + 2 for 10^power438if (abs_number < 1000) {439res = abs_number<<2;440} else if (abs_number < 10000) {441res = ((uint16_t)roundf(abs_number * 0.1f)<<2)|0x1;442} else if (abs_number < 100000) {443res = ((uint16_t)roundf(abs_number * 0.01f)<<2)|0x2;444} else if (abs_number < 1024000) {445res = ((uint16_t)roundf(abs_number * 0.001f)<<2)|0x3;446} else { // transmit max possible value (0x3FF x 10^3 = 1023000)447res = 0xFFF;448}449if (number < 0) { // if number is negative, add sign bit in front450res |= 0x1<<12;451}452}453return res;454}455456/*457* Push user data down the telemetry link by responding to sensor polling (sport)458* or by using dedicated slots in the scheduler (fport)459* for SPort and FPort protocols (X-receivers)460*/461bool AP_Frsky_SPort::sport_telemetry_push(uint8_t sensor, uint8_t frame, uint16_t appid, int32_t data)462{463WITH_SEMAPHORE(_sport_push_buffer.sem);464if (_sport_push_buffer.pending) {465return false;466}467_sport_push_buffer.packet.sensor = sensor;468_sport_push_buffer.packet.frame = frame;469_sport_push_buffer.packet.appid = appid;470_sport_push_buffer.packet.data = static_cast<uint32_t>(data);471_sport_push_buffer.pending = true;472return true;473}474475namespace AP {476AP_Frsky_SPort *frsky_sport() {477return AP_Frsky_SPort::get_singleton();478}479};480481#endif // AP_FRSKY_SPORT_TELEM_ENABLED482483484