APM:Libraries
driver_cc2500.h
Go to the documentation of this file.
1 /*
2  low level driver for the TI CC2500 radio on SPI
3 
4  With thanks to betaflight
5 */
6 
7 #pragma once
8 
9 #include <AP_HAL/AP_HAL.h>
10 
11 enum {
12  CC2500_00_IOCFG2 = 0x00, // GDO2 output pin configuration
13  CC2500_01_IOCFG1 = 0x01, // GDO1 output pin configuration
14  CC2500_02_IOCFG0 = 0x02, // GDO0 output pin configuration
15  CC2500_03_FIFOTHR = 0x03, // RX FIFO and TX FIFO thresholds
16  CC2500_04_SYNC1 = 0x04, // Sync word, high byte
17  CC2500_05_SYNC0 = 0x05, // Sync word, low byte
18  CC2500_06_PKTLEN = 0x06, // Packet length
19  CC2500_07_PKTCTRL1 = 0x07, // Packet automation control
20  CC2500_08_PKTCTRL0 = 0x08, // Packet automation control
21  CC2500_09_ADDR = 0x09, // Device address
22  CC2500_0A_CHANNR = 0x0A, // Channel number
23  CC2500_0B_FSCTRL1 = 0x0B, // Frequency synthesizer control
24  CC2500_0C_FSCTRL0 = 0x0C, // Frequency synthesizer control
25  CC2500_0D_FREQ2 = 0x0D, // Frequency control word, high byte
26  CC2500_0E_FREQ1 = 0x0E, // Frequency control word, middle byte
27  CC2500_0F_FREQ0 = 0x0F, // Frequency control word, low byte
28  CC2500_10_MDMCFG4 = 0x10, // Modem configuration
29  CC2500_11_MDMCFG3 = 0x11, // Modem configuration
30  CC2500_12_MDMCFG2 = 0x12, // Modem configuration
31  CC2500_13_MDMCFG1 = 0x13, // Modem configuration
32  CC2500_14_MDMCFG0 = 0x14, // Modem configuration
33  CC2500_15_DEVIATN = 0x15, // Modem deviation setting
34  CC2500_16_MCSM2 = 0x16, // Main Radio Cntrl State Machine config
35  CC2500_17_MCSM1 = 0x17, // Main Radio Cntrl State Machine config
36  CC2500_18_MCSM0 = 0x18, // Main Radio Cntrl State Machine config
37  CC2500_19_FOCCFG = 0x19, // Frequency Offset Compensation config
38  CC2500_1A_BSCFG = 0x1A, // Bit Synchronization configuration
39  CC2500_1B_AGCCTRL2 = 0x1B, // AGC control
40  CC2500_1C_AGCCTRL1 = 0x1C, // AGC control
41  CC2500_1D_AGCCTRL0 = 0x1D, // AGC control
42  CC2500_1E_WOREVT1 = 0x1E, // High byte Event 0 timeout
43  CC2500_1F_WOREVT0 = 0x1F, // Low byte Event 0 timeout
44  CC2500_20_WORCTRL = 0x20, // Wake On Radio control
45  CC2500_21_FREND1 = 0x21, // Front end RX configuration
46  CC2500_22_FREND0 = 0x22, // Front end TX configuration
47  CC2500_23_FSCAL3 = 0x23, // Frequency synthesizer calibration
48  CC2500_24_FSCAL2 = 0x24, // Frequency synthesizer calibration
49  CC2500_25_FSCAL1 = 0x25, // Frequency synthesizer calibration
50  CC2500_26_FSCAL0 = 0x26, // Frequency synthesizer calibration
51  CC2500_27_RCCTRL1 = 0x27, // RC oscillator configuration
52  CC2500_28_RCCTRL0 = 0x28, // RC oscillator configuration
53  CC2500_29_FSTEST = 0x29, // Frequency synthesizer cal control
54  CC2500_2A_PTEST = 0x2A, // Production test
55  CC2500_2B_AGCTEST = 0x2B, // AGC test
56  CC2500_2C_TEST2 = 0x2C, // Various test settings
57  CC2500_2D_TEST1 = 0x2D, // Various test settings
58  CC2500_2E_TEST0 = 0x2E, // Various test settings
59 
60  // Status registers
61  CC2500_30_PARTNUM = 0x30, // Part number
62  CC2500_31_VERSION = 0x31, // Current version number
63  CC2500_32_FREQEST = 0x32, // Frequency offset estimate
64  CC2500_33_LQI = 0x33, // Demodulator estimate for link quality
65  CC2500_34_RSSI = 0x34, // Received signal strength indication
66  CC2500_35_MARCSTATE = 0x35, // Control state machine state
67  CC2500_36_WORTIME1 = 0x36, // High byte of WOR timer
68  CC2500_37_WORTIME0 = 0x37, // Low byte of WOR timer
69  CC2500_38_PKTSTATUS = 0x38, // Current GDOx status and packet status
70  CC2500_39_VCO_VC_DAC = 0x39, // Current setting from PLL cal module
71  CC2500_3A_TXBYTES = 0x3A, // Underflow and # of bytes in TXFIFO
72  CC2500_3B_RXBYTES = 0x3B, // Overflow and # of bytes in RXFIFO
73 
74  // Multi byte memory locations
78 };
79 
80 // Definitions for burst/single access to registers
81 #define CC2500_WRITE_SINGLE 0x00
82 #define CC2500_WRITE_BURST 0x40
83 #define CC2500_READ_SINGLE 0x80
84 #define CC2500_READ_BURST 0xC0
85 
86 // Strobe commands
87 #define CC2500_SRES 0x30 // Reset chip.
88 #define CC2500_SFSTXON \
89  0x31 // Enable and calibrate frequency synthesizer (if MCSM0.FS_AUTOCAL=1).
90  // If in RX/TX: Go to a wait state where only the synthesizer is
91  // running (for quick RX / TX turnaround).
92 #define CC2500_SXOFF 0x32 // Turn off crystal oscillator.
93 #define CC2500_SCAL 0x33 // Calibrate frequency synthesizer and turn it off
94  // (enables quick start).
95 #define CC2500_SRX \
96  0x34 // Enable RX. Perform calibration first if coming from IDLE and
97  // MCSM0.FS_AUTOCAL=1.
98 #define CC2500_STX \
99  0x35 // In IDLE state: Enable TX. Perform calibration first if
100  // MCSM0.FS_AUTOCAL=1. If in RX state and CCA is enabled:
101  // Only go to TX if channel is clear.
102 #define CC2500_SIDLE \
103  0x36 // Exit RX / TX, turn off frequency synthesizer and exit
104  // Wake-On-Radio mode if applicable.
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
113  // bytes for simpler software.
114 //----------------------------------------------------------------------------------
115 // Chip Status Byte
116 //----------------------------------------------------------------------------------
117 
118 // Bit fields in the chip status byte
119 #define CC2500_STATUS_CHIP_RDYn_BM 0x80
120 #define CC2500_STATUS_STATE_BM 0x70
121 #define CC2500_STATUS_FIFO_BYTES_AVAILABLE_BM 0x0F
122 
123 // Chip states
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
132 
133 //----------------------------------------------------------------------------------
134 // Other register bit fields
135 //----------------------------------------------------------------------------------
136 #define CC2500_LQI_CRC_OK_BM 0x80
137 #define CC2500_LQI_EST_BM 0x7F
138 
139 // CC2500 driver class
141 public:
143 
144  void ReadFifo(uint8_t *dpbuffer, uint8_t len);
145  void WriteFifo(const uint8_t *dpbuffer, uint8_t len);
146 
147  void ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t length);
148  void WriteRegisterMulti(uint8_t address, const uint8_t *data, uint8_t length);
149 
150  uint8_t ReadReg(uint8_t reg);
151  uint8_t Strobe(uint8_t address);
152  void WriteReg(uint8_t address, uint8_t data);
153  void WriteRegCheck(uint8_t address, uint8_t data);
154  void SetPower(uint8_t power);
155  bool Reset(void);
156 
157  bool lock_bus(void) {
159  }
160  void unlock_bus(void) {
161  dev->get_semaphore()->give();
162  }
163 
164 private:
166 };
uint8_t ReadReg(uint8_t reg)
void unlock_bus(void)
bool Reset(void)
void ReadFifo(uint8_t *dpbuffer, uint8_t len)
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
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)
bool lock_bus(void)
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)
virtual bool give()=0
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)