81 #define CC2500_WRITE_SINGLE 0x00 82 #define CC2500_WRITE_BURST 0x40 83 #define CC2500_READ_SINGLE 0x80 84 #define CC2500_READ_BURST 0xC0 87 #define CC2500_SRES 0x30 // Reset chip. 88 #define CC2500_SFSTXON \ 89 0x31 // Enable and calibrate frequency synthesizer (if MCSM0.FS_AUTOCAL=1). 92 #define CC2500_SXOFF 0x32 // Turn off crystal oscillator. 93 #define CC2500_SCAL 0x33 // Calibrate frequency synthesizer and turn it off 96 0x34 // Enable RX. Perform calibration first if coming from IDLE and 99 0x35 // In IDLE state: Enable TX. Perform calibration first if 102 #define CC2500_SIDLE \ 103 0x36 // Exit RX / TX, turn off frequency synthesizer and exit 105 #define CC2500_SAFC 0x37 // Perform AFC adjustment of the frequency synthesizer 106 #define CC2500_SWOR 0x38 // Start automatic RX polling sequence (Wake-on-Radio) 107 #define CC2500_SPWD 0x39 // Enter power down mode when CSn goes high. 108 #define CC2500_SFRX 0x3A // Flush the RX FIFO buffer. 109 #define CC2500_SFTX 0x3B // Flush the TX FIFO buffer. 110 #define CC2500_SWORRST 0x3C // Reset real time clock. 111 #define CC2500_SNOP \ 112 0x3D // No operation. May be used to pad strobe commands to two 119 #define CC2500_STATUS_CHIP_RDYn_BM 0x80 120 #define CC2500_STATUS_STATE_BM 0x70 121 #define CC2500_STATUS_FIFO_BYTES_AVAILABLE_BM 0x0F 124 #define CC2500_STATE_IDLE 0x00 125 #define CC2500_STATE_RX 0x10 126 #define CC2500_STATE_TX 0x20 127 #define CC2500_STATE_FSTXON 0x30 128 #define CC2500_STATE_CALIBRATE 0x40 129 #define CC2500_STATE_SETTLING 0x50 130 #define CC2500_STATE_RX_OVERFLOW 0x60 131 #define CC2500_STATE_TX_UNDERFLOW 0x70 136 #define CC2500_LQI_CRC_OK_BM 0x80 137 #define CC2500_LQI_EST_BM 0x7F 144 void ReadFifo(uint8_t *dpbuffer, uint8_t len);
145 void WriteFifo(
const uint8_t *dpbuffer, uint8_t len);
151 uint8_t
Strobe(uint8_t address);
152 void WriteReg(uint8_t address, uint8_t data);
uint8_t ReadReg(uint8_t reg)
void ReadFifo(uint8_t *dpbuffer, uint8_t len)
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
void WriteFifo(const uint8_t *dpbuffer, uint8_t len)
void WriteReg(uint8_t address, uint8_t data)
virtual Semaphore * get_semaphore() override=0
void WriteRegisterMulti(uint8_t address, const uint8_t *data, uint8_t length)
void ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t length)
AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev
void SetPower(uint8_t power)
void WriteRegCheck(uint8_t address, uint8_t data)
Radio_CC2500(AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev)
uint8_t Strobe(uint8_t address)