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.h
Views: 1798
#pragma once12#include "AP_Frsky_Backend.h"34#if AP_FRSKY_SPORT_TELEM_ENABLED56class AP_Frsky_SPort : public AP_Frsky_Backend7{89public:1011AP_Frsky_SPort(AP_HAL::UARTDriver *port) : AP_Frsky_Backend(port) {12singleton = this;13}1415/* Do not allow copies */16CLASS_NO_COPY(AP_Frsky_SPort);1718void send() override;19// send an sport packet by responding to the specified polled sensor20bool sport_telemetry_push(const uint8_t sensor, const uint8_t frame, const uint16_t appid, const int32_t data);21// utility method to pack numbers in a compact size22uint16_t prep_number(int32_t const number, const uint8_t digits, const uint8_t power);2324static AP_Frsky_SPort *get_singleton(void) {25return singleton;26}2728protected:2930void send_sport_frame(uint8_t frame, uint16_t appid, uint32_t data);3132struct {33bool send_latitude;34bool send_airspeed; // toggles 0x5005 between airspeed and groundspeed35uint32_t gps_lng_sample;36uint8_t new_byte;37} _passthrough;3839uint32_t calc_gps_latlng(bool &send_latitude);40static uint8_t calc_sensor_id(const uint8_t physical_id);4142struct {43sport_packet_t packet;44bool pending = false;45HAL_Semaphore sem;46} _sport_push_buffer;4748private:4950struct {51bool sport_status;52bool gps_refresh;53bool vario_refresh;54uint8_t fas_call;55uint8_t gps_call;56uint8_t vario_call;57uint8_t various_call;58uint8_t rpm_call;59} _SPort;6061static AP_Frsky_SPort *singleton;6263};6465namespace AP {66AP_Frsky_SPort *frsky_sport();67};6869#endif // AP_FRSKY_SPORT_TELEM_ENABLED707172