31 virtual bool init(
void) = 0;
34 virtual bool reset(
void) = 0;
37 virtual bool send(
const uint8_t *pkt, uint16_t len) = 0;
49 virtual uint16_t
read(uint8_t
chan) = 0;
55 virtual void update(
void) = 0;
85 return (uint8_t)radio.
pps_chan.get();
virtual const AP_Radio::stats & get_stats(void)=0
uint8_t get_tx_rssi_chan(void) const
uint8_t get_debug_level(void) const
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
uint8_t get_rssi_chan(void) const
uint8_t get_factory_test(void) const
virtual void update(void)=0
virtual bool reset(void)=0
virtual bool send(const uint8_t *pkt, uint16_t len)=0
AP_Radio_backend(AP_Radio &radio)
bool get_telem_enable(void) const
uint8_t get_autobind_rssi(void) const
virtual uint16_t read(uint8_t chan)=0
int8_t get_fcc_test(void) const
bool get_disable_crc(void) const
virtual void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
void set_tx_max_power_default(uint8_t v)
uint8_t get_stick_mode(void) const
virtual void start_recv_bind(void)=0
virtual ~AP_Radio_backend()
uint8_t get_tx_buzzer_adjust(void) const
virtual void set_wifi_channel(uint8_t channel)=0
uint8_t get_transmit_power(void) const
AP_HAL::AnalogSource * chan
uint8_t get_autobind_time(void) const
virtual bool init(void)=0
uint8_t get_tx_pps_chan(void) const
uint8_t get_tx_max_power(void) const
virtual uint32_t last_recv_us(void)=0
virtual uint8_t num_channels(void)=0
uint8_t get_pps_chan(void) const
virtual uint32_t get_tx_version(void)=0
AP_Radio::ap_radio_protocol get_protocol(void) const