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_Backend.h
Views: 1798
#pragma once12#include "AP_Frsky_config.h"34#if AP_FRSKY_TELEM_ENABLED56#include <GCS_MAVLink/GCS_MAVLink.h>78class AP_Frsky_Backend9{10public:1112AP_Frsky_Backend(AP_HAL::UARTDriver *port) :13_port(port) { }1415virtual ~AP_Frsky_Backend() {}1617virtual bool init();18virtual void send() = 0;1920typedef union {21struct PACKED {22uint8_t sensor;23uint8_t frame;24uint16_t appid;25uint32_t data;26};27uint8_t raw[8];28} sport_packet_t;2930// SPort is at 57600, D overrides this31virtual uint32_t initial_baud() const32{33return 57600;34}3536// get next telemetry data for external consumers of SPort data37virtual bool get_telem_data(sport_packet_t* packet_array, uint8_t &packet_count, const uint8_t max_size)38{39return false;40}4142#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL43virtual bool set_telem_data(const uint8_t frame, const uint16_t appid, const uint32_t data)44{45return false;46}47#endif4849virtual void queue_text_message(MAV_SEVERITY severity, const char *text) { }5051protected:5253AP_HAL::UARTDriver *_port; // UART used to send data to FrSky receiver5455virtual bool init_serial_port();5657void calc_nav_alt(void);58void calc_gps_position(void);59bool calc_rpm(const uint8_t instance, int32_t &value) const;6061float get_vspeed_ms(void);6263// methods to convert flight controller data to FrSky D or SPort format64float format_gps(float dec);6566struct {67int32_t vario_vspd;68char lat_ns, lon_ew;69uint16_t latdddmm;70uint16_t latmmmm;71uint16_t londddmm;72uint16_t lonmmmm;73uint16_t alt_gps_meters;74uint16_t alt_gps_cm;75uint16_t alt_nav_meters;76uint16_t alt_nav_cm;77int16_t speed_in_meter;78uint16_t speed_in_centimeter;79uint16_t yaw;80} _SPort_data;8182/*83for FrSky D protocol (D-receivers)84*/85// FrSky sensor hub data IDs86static const uint8_t DATA_ID_GPS_ALT_BP = 0x01;87static const uint8_t DATA_ID_TEMP1 = 0x02;88static const uint8_t DATA_ID_FUEL = 0x04;89static const uint8_t DATA_ID_TEMP2 = 0x05;90static const uint8_t DATA_ID_GPS_ALT_AP = 0x09;91static const uint8_t DATA_ID_BARO_ALT_BP = 0x10;92static const uint8_t DATA_ID_GPS_SPEED_BP = 0x11;93static const uint8_t DATA_ID_GPS_LONG_BP = 0x12;94static const uint8_t DATA_ID_GPS_LAT_BP = 0x13;95static const uint8_t DATA_ID_GPS_COURS_BP = 0x14;96static const uint8_t DATA_ID_GPS_SPEED_AP = 0x19;97static const uint8_t DATA_ID_GPS_LONG_AP = 0x1A;98static const uint8_t DATA_ID_GPS_LAT_AP = 0x1B;99static const uint8_t DATA_ID_BARO_ALT_AP = 0x21;100static const uint8_t DATA_ID_GPS_LONG_EW = 0x22;101static const uint8_t DATA_ID_GPS_LAT_NS = 0x23;102static const uint8_t DATA_ID_CURRENT = 0x28;103static const uint8_t DATA_ID_VFAS = 0x39;104105static const uint8_t START_STOP_D = 0x5E;106static const uint8_t BYTESTUFF_D = 0x5D;107108/*109for FrSky X protocol (X-receivers)110*/111// FrSky 2 bytes DATA IDs;112static const uint16_t ALT_ID = 0x010F;113static const uint16_t VARIO_ID = 0x011F;114static const uint16_t CURR_ID = 0x020F;115static const uint16_t VFAS_ID = 0x021F;116static const uint16_t TEMP1_ID = 0x040F;117static const uint16_t TEMP2_ID = 0x041F;118static const uint16_t RPM1_ID = 0x050E;119static const uint16_t RPM2_ID = 0x050F;120static const uint16_t FUEL_ID = 0x060F;121static const uint16_t GPS_LONG_LATI_FIRST_ID = 0x0800;122static const uint16_t GPS_ALT_ID = 0x082F;123static const uint16_t GPS_SPEED_ID = 0x083F;124static const uint16_t GPS_COURS_ID = 0x084F;125static const uint16_t DIY_FIRST_ID = 0x5000;126127static const uint8_t FRAME_HEAD = 0x7E;128static const uint8_t FRAME_DLE = 0x7D;129static const uint8_t FRAME_XOR = 0x20;130131static const uint8_t SPORT_DATA_FRAME = 0x10;132133// for FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)134static const uint8_t SENSOR_ID_VARIO = 0x00; // Sensor ID 0135static const uint8_t SENSOR_ID_FAS = 0x22; // Sensor ID 2136static const uint8_t SENSOR_ID_GPS = 0x83; // Sensor ID 3137static const uint8_t SENSOR_ID_RPM = 0xE4; // Sensor ID 4138static const uint8_t SENSOR_ID_SP2UR = 0xC6; // Sensor ID 6139140enum frsky_options_e : uint8_t {141OPTION_AIRSPEED_AND_GROUNDSPEED = 1U<<0,142};143144private:145146void loop(void);147148};149150#endif // AP_FRSKY_TELEM_ENABLED151152153