ardupilot/libraries/AP_Frsky_Telem/AP_Frsky_SPort.h

50 lines
972 B
C
Raw Normal View History

2020-09-28 01:31:38 -03:00
#pragma once
#include "AP_Frsky_Backend.h"
class AP_Frsky_SPort : public AP_Frsky_Backend
{
2020-09-28 01:31:38 -03:00
public:
using AP_Frsky_Backend::AP_Frsky_Backend;
void send() override;
typedef union {
struct PACKED {
uint8_t sensor;
uint8_t frame;
uint16_t appid;
uint32_t data;
};
uint8_t raw[8];
} sport_packet_t;
2020-09-28 01:31:38 -03:00
protected:
void send_sport_frame(uint8_t frame, uint16_t appid, uint32_t data);
struct PACKED {
2020-09-28 01:31:38 -03:00
bool send_latitude; // sizeof(bool) = 4 ?
uint32_t gps_lng_sample;
uint8_t new_byte;
} _passthrough;
uint32_t calc_gps_latlng(bool &send_latitude);
2020-09-28 01:31:38 -03:00
static uint8_t calc_sensor_id(const uint8_t physical_id);
2020-09-28 01:31:38 -03:00
private:
struct {
2020-09-28 01:31:38 -03:00
bool sport_status;
bool gps_refresh;
bool vario_refresh;
uint8_t fas_call;
uint8_t gps_call;
uint8_t vario_call;
uint8_t various_call;
} _SPort;
};