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_Passthrough.h
Views: 1798
#pragma once12#include "AP_Frsky_SPort.h"34#if AP_FRSKY_SPORT_PASSTHROUGH_ENABLED56#include <AP_RCTelemetry/AP_RCTelemetry.h>78#include "AP_Frsky_SPortParser.h"9#include "AP_Frsky_MAVlite.h"1011#include "AP_Frsky_Telem.h"1213#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL14#include "AP_Frsky_MAVlite_SPortToMAVlite.h"15#include "AP_Frsky_MAVlite_MAVliteToSPort.h"16#include "AP_Frsky_MAVliteMsgHandler.h"1718#define SPORT_TX_PACKET_DUPLICATES 1 // number of duplicates packets we send (fport only)19#endif2021class AP_Frsky_SPort_Passthrough : public AP_Frsky_SPort, public AP_RCTelemetry22{23public:2425AP_Frsky_SPort_Passthrough(AP_HAL::UARTDriver *port, bool use_external_data, AP_Frsky_Parameters *&frsky_parameters) :26AP_Frsky_SPort(port),27AP_RCTelemetry(WFQ_LAST_ITEM),28_frsky_parameters(frsky_parameters),29_use_external_data(use_external_data)30{31singleton = this;32}3334static AP_Frsky_SPort_Passthrough *get_singleton(void) {35return singleton;36}3738bool init() override;39bool init_serial_port() override;4041// passthrough WFQ scheduler42bool is_packet_ready(uint8_t idx, bool queue_empty) override;43void process_packet(uint8_t idx) override;44void adjust_packet_weight(bool queue_empty) override;45// setup ready for passthrough operation46void setup_wfq_scheduler(void) override;4748bool get_next_msg_chunk(void) override;4950bool get_telem_data(sport_packet_t* packet_array, uint8_t &packet_count, const uint8_t max_size) override;51#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL52bool set_telem_data(const uint8_t frame, const uint16_t appid, const uint32_t data) override;53#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL5455void queue_text_message(MAV_SEVERITY severity, const char *text) override56{57AP_RCTelemetry::queue_message(severity, text);58}5960enum PassthroughPacketType : uint8_t {61TEXT = 0, // 0x5000 status text (dynamic)62ATTITUDE = 1, // 0x5006 Attitude and range (dynamic)63GPS_LAT = 2, // 0x800 GPS lat64GPS_LON = 3, // 0x800 GPS lon65VEL_YAW = 4, // 0x5005 Vel and Yaw66AP_STATUS = 5, // 0x5001 AP status67GPS_STATUS = 6, // 0x5002 GPS status68HOME = 7, // 0x5004 Home69BATT_2 = 8, // 0x5008 Battery 2 status70BATT_1 = 9, // 0x5008 Battery 1 status71PARAM = 10, // 0x5007 parameters72RPM = 11, // 0x500A rpm sensors 1 and 273UDATA = 12, // user data74#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL75MAV = 13, // mavlite76#endif //HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL77TERRAIN = 14, // 0x500B terrain data78WIND = 15, // 0x500C wind data79WAYPOINT = 16, // 0x500D waypoint data80WFQ_LAST_ITEM // must be last81};8283protected:8485void send() override;8687private:8889AP_Frsky_Parameters *&_frsky_parameters;9091enum PassthroughParam : uint8_t {92NONE = 0,93FRAME_TYPE = 1,94BATT_FS_VOLTAGE = 2,95BATT_FS_CAPACITY = 3,96BATT_CAPACITY_1 = 4,97BATT_CAPACITY_2 = 5,98TELEMETRY_FEATURES = 699};100101enum PassthroughFeatures : uint8_t {102BIDIR = 0,103SCRIPTING = 1,104};105106// methods to convert flight controller data to FrSky SPort Passthrough (OpenTX) format107uint32_t calc_param(void);108uint32_t calc_batt(uint8_t instance);109uint32_t calc_ap_status(void);110uint32_t calc_home(void);111uint32_t calc_velandyaw(void);112uint32_t calc_attiandrng(void);113uint32_t calc_rpm(void);114uint32_t calc_terrain(void);115uint32_t calc_wind(void);116uint32_t calc_waypoint(void);117118// use_external_data is set when this library will119// be providing data to another transport, such as FPort120bool _use_external_data;121122struct {123sport_packet_t packet;124bool pending;125} external_data;126127struct {128uint32_t chunk; // a "chunk" (four characters/bytes) at a time of the queued message to be sent129uint8_t repeats; // send each message "chunk" 3 times to make sure the entire messsage gets through without getting cut130uint8_t char_index; // index of which character to get in the message131} _msg_chunk;132133// passthrough default sensor id134uint8_t downlink_sensor_id = 0x1B;135136#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL137// bidirectional sport telemetry138struct {139uint8_t uplink_sensor_id = 0x0D;140uint8_t downlink1_sensor_id = 0x34;141uint8_t downlink2_sensor_id = 0x67;142uint8_t tx_packet_duplicates;143ObjectBuffer_TS<AP_Frsky_SPort::sport_packet_t> rx_packet_queue{SPORT_PACKET_QUEUE_LENGTH};144ObjectBuffer_TS<AP_Frsky_SPort::sport_packet_t> tx_packet_queue{SPORT_PACKET_QUEUE_LENGTH};145} _SPort_bidir;146147AP_Frsky_SPortParser _sport_handler;148AP_Frsky_MAVlite_SPortToMAVlite sport_to_mavlite;149AP_Frsky_MAVlite_MAVliteToSPort mavlite_to_sport;150151// tx/rx sport packet processing152void queue_rx_packet(const AP_Frsky_SPort::sport_packet_t sp);153void process_rx_queue(void);154void process_tx_queue(void);155156// create an object to handle incoming mavlite messages; a157// callback method is provided to allow the handler to send responses158bool send_message(const AP_Frsky_MAVlite_Message &txmsg);159AP_Frsky_MAVliteMsgHandler mavlite{FUNCTOR_BIND_MEMBER(&AP_Frsky_SPort_Passthrough::send_message, bool, const AP_Frsky_MAVlite_Message &)};160#endif161void set_sensor_id(AP_Int8 idx, uint8_t &sensor);162void send_sport_frame(uint8_t frame, uint16_t appid, uint32_t data);163164// true if we need to respond to the last polling byte165bool is_passthrough_byte(const uint8_t byte) const;166167uint8_t _paramID;168169uint32_t calc_gps_status(void);170171static AP_Frsky_SPort_Passthrough *singleton;172};173174namespace AP {175AP_Frsky_SPort_Passthrough *frsky_passthrough_telem();176};177178179#endif // AP_FRSKY_SPORT_PASSTHROUGH_ENABLED180181182