24 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS 29 #define CC2500_MAX_CHANNELS 16 37 bool init(
void)
override;
40 bool reset(
void)
override;
43 bool send(
const uint8_t *pkt, uint16_t
len)
override;
55 uint16_t
read(uint8_t
chan)
override;
61 void update(
void)
override;
66 return (uint16_t(
tx_date.firmware_year)<<12) + (uint16_t(
tx_date.firmware_month)<<8) +
tx_date.firmware_day;
127 bool tuneRx(uint8_t ccLen, uint8_t *packet);
134 uint16_t
calc_crc(
const uint8_t *data, uint8_t len);
135 bool check_crc(uint8_t ccLen, uint8_t *packet);
150 uint8_t bindHopData[47];
208 #endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
void nextChannel(uint8_t skip)
static thread_t * _irq_handler_ctx
bool send(const uint8_t *pkt, uint16_t len) override
static void trigger_timeout_event(void *arg)
AP_Radio_cc2500(AP_Radio &radio)
uint16_t pwm_channels[CC2500_MAX_CHANNELS]
bool tuneRx(uint8_t ccLen, uint8_t *packet)
void update(void) override
void save_bind_info(void)
bool getBindData(uint8_t ccLen, uint8_t *packet)
AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev
AP_Radio::stats last_stats
uint16_t read(uint8_t chan) override
void send_D16_telemetry(void)
void setChannel(uint8_t channel)
struct telem_status t_status
enum AP_Radio_cc2500::@167 protocolState
void start_recv_bind(void) override
static uint32_t irq_time_us
uint32_t last_recv_us(void) override
struct AP_Radio_cc2500::@169 tx_date
bool reset(void) override
uint8_t num_channels(void) override
#define CC2500_MAX_CHANNELS
const uint32_t sync_time_us
void initialiseData(uint8_t adr)
bool handle_D16_packet(const uint8_t *packet)
bool check_crc(uint8_t ccLen, uint8_t *packet)
static virtual_timer_t timeout_vt
static void trigger_irq_radio_event(void)
void parse_frSkyX(const uint8_t *packet)
static AP_Radio_cc2500 * radio_instance
bool handle_SRT_packet(const uint8_t *packet)
void send_SRT_telemetry(void)
bool check_best_LQI(void)
void set_wifi_channel(uint8_t channel)
struct AP_Radio_cc2500::@168 fwupload
const AP_Radio::stats & get_stats(void) override
uint16_t calc_crc(const uint8_t *data, uint8_t len)
static const config radio_config[]
bool load_bind_info(void)
uint32_t get_tx_version(void) override
void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m) override
static void irq_handler_thd(void *arg)
static const uint16_t bind_magic