36 uint8_t buf[length+1];
38 memcpy(&buf[1], data, length);
63 const uint8_t patable[8] = {
uint8_t ReadReg(uint8_t reg)
void ReadFifo(uint8_t *dpbuffer, uint8_t len)
#define CC2500_WRITE_BURST
void WriteFifo(const uint8_t *dpbuffer, uint8_t len)
void WriteReg(uint8_t address, uint8_t data)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static AP_HAL::OwnPtr< AP_HAL::Device > dev
void WriteRegisterMulti(uint8_t address, const uint8_t *data, uint8_t length)
void ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t length)
#define CC2500_READ_BURST
#define CC2500_READ_SINGLE
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev
void SetPower(uint8_t power)
virtual void delay_microseconds(uint16_t us)=0
void WriteRegCheck(uint8_t address, uint8_t data)
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Radio_CC2500(AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev)
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
AP_HAL::Scheduler * scheduler
uint8_t Strobe(uint8_t address)