Radio Structures in OOP

Dependencies:   mbed mbed-rtos

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers CC1101.cpp Source File

CC1101.cpp

00001 #include "CC1101.h"
00002 
00003 
00004 // Default constructor
00005 CC1101::CC1101() :
00006     CommLink()
00007 {
00008 }
00009 
00010 // Main constructor
00011 CC1101::CC1101(PinName mosi, PinName miso, PinName sck, PinName cs, PinName int_pin) :
00012     CommLink(mosi, miso, sck, cs, int_pin)
00013 {
00014     // [X] - 1 - Setup the chip and only signal the base class if device is tested and confirmed to be electrically connected
00015     if(powerUp()) {
00016         
00017         LOG("CC1101 Failure");
00018         
00019     } else {
00020         
00021         // [X] - 2 - Call the base class method for beginning full class operation with threads
00022         // =================
00023         CommLink::ready();
00024         LOG("CC1101 Ready!");
00025         
00026     }
00027 }
00028 
00029 // Deconstructor
00030 CC1101::~CC1101()
00031 {
00032     if (_spi)
00033         delete _spi;
00034     if (_cs)
00035         delete _cs;
00036     if (_int_in)
00037         delete _int_in;
00038 }
00039 
00040 
00041 int32_t CC1101::powerUp(void)
00042 {
00043 
00044 #if CCXXX1_DEBUG_MODE > 0
00045     EVENT("CC1101 RADIO TRANSCEIVER INITILIZATION");
00046 #endif
00047 
00048     set_init_vars();
00049     freq(CCXXX1_BASE_FREQUENCY);
00050     interface_freq(CCXXX1_IF_FREQUENCY);
00051     assign_channel_spacing(200000);    // 200kHz
00052     datarate(250000);  // 250 kBaud
00053     set_rf_settings();
00054     init();
00055     return selfTest();
00056 }
00057 
00058 
00059 bool CC1101::isConnected(void)
00060 {
00061     // [] - 1 - Perform a check to ensure the CC1101 can provide communication with a secondary base station link
00062     // =================
00063     // Note: This does not necessarily mean the link must be reliable, this only needs to determine: `Can the perheripial provide communication with a 2nd initialized CC1101?`
00064 
00065     // [] - 2 - Return true/false for indicating a connected communication link
00066     // =================
00067 
00068     return true;
00069 }
00070 
00071 
00072 void CC1101::reset(void)
00073 {
00074     // [X] - 1 - Perform a soft reset for the CC1101 transceiver
00075     // =================
00076     strobe(CCXXX1_SRES);
00077 }
00078 
00079 
00080 int32_t CC1101::selfTest(void)
00081 {
00082     // [X] - 1 - Get the chip's version number and fail if different from what was expected.
00083     _chip_version = status(CCXXX1_VERSION);
00084 
00085     if (_chip_version != CCXXX1_EXPECTED_VERSION_NUMBER) {
00086 
00087         // send message over serial port
00088         WARNING(
00089             "FATAL ERROR\r\n"
00090             "  Wrong version number returned from chip's 'VERSION' register (Addr: 0x%02X)\r\n"
00091             "\r\n"
00092             "  Expected: 0x%02X\r\n"
00093             "  Found:    0x%02X\r\n"
00094             "\r\n"
00095             "  Troubleshooting Tips:\r\n"
00096             "    - Check that the chip is fully connected with no soldering errors\r\n"
00097             "    - Determine if chip is newer version & update firmware\r\n"
00098             , CCXXX1_VERSION, CCXXX1_EXPECTED_VERSION_NUMBER, _chip_version);
00099 
00100         return -1;  // negative numbers mean error occurred
00101     }
00102 
00103     return 0;   // success
00104 }
00105 
00106 
00107 void CC1101::set_init_vars(void)
00108 {
00109     // define the initial state of an unselected chip
00110     *_cs = 1;
00111     _channel = 1;
00112     _address = 0x00;
00113 
00114     // turn off address packet filtering and assign 0 (broadcast address) to the address value
00115     _pck_control.addr_check = ADDR_OFF;
00116 
00117     // these values determine how the CC1101 will handel a packet
00118     _pck_control.whitening_en = false;
00119 
00120     // enable CRC calculation in TX and CRC checking in RX
00121     _pck_control.crc_en = true;
00122 
00123     // enable automatically flushing the RX buffer on a bad CRC (only works if 1 packet is in the RX buffer)
00124     _pck_control.autoflush_en = true;
00125 
00126     // enable appending 2 status bytes to the end of every packet that includes the CRC and
00127     _pck_control.status_field_en = true;
00128 
00129     // normal packet mode uses RX and TX buffers
00130     _pck_control.format_type = FORMAT_DEFAULT;
00131 
00132     // setup how the payload of the packet is transmitted - default to a fixed length of 61 bytes
00133     _pck_control.length_type = PACKET_VARIABLE;
00134     //_pck_control.length_type = PACKET_FIXED;
00135     _pck_control.size = 61; // indicates max packet size when using variable packet types
00136 
00137     // this is a preamble threshold for determining when a packet should be accepted
00138     _pck_control.preamble_thresh = 2;
00139 
00140     // these values determine how the frequency bands and channels are distributed as well as defining the modulation type
00141     _modem.dc_filter_off_en = false;
00142     _modem.manchester_encode_en = false;
00143     _modem.fec_en = false;
00144 
00145     // bandwidth configurations
00146     _modem.channel_bw = 2;
00147     _modem.channel_bw_exp = 0;
00148     _modem.channel_space_exp = 2;
00149     _modem.data_rate_exp = 13;
00150 
00151     _modem.mod_type = MOD_GFSK;
00152     _modem.sync_mode = SYNC_HIGH_ALLOW_TWO;
00153     _modem.preamble_bytes = PREAM_FOUR;
00154 }
00155 
00156 
00157 void CC1101::put_rf_settings()
00158 {
00159 #if DEBUG_MODE > 0
00160     LOG("Writing configuration registers...");
00161 #endif
00162     write_reg(CCXXX1_IOCFG2,   rfSettings.IOCFG2);
00163     write_reg(CCXXX1_IOCFG1,   rfSettings.IOCFG1);
00164     write_reg(CCXXX1_IOCFG0,   rfSettings.IOCFG0);
00165     write_reg(CCXXX1_FIFOTHR,  rfSettings.FIFOTHR);
00166     // SYNC1
00167     // SYNC0
00168     write_reg(CCXXX1_PCKLEN,   rfSettings.PCKLEN);
00169     write_reg(CCXXX1_PCKCTRL1, rfSettings.PCKCTRL1);
00170     write_reg(CCXXX1_PCKCTRL0, rfSettings.PCKCTRL0);
00171     write_reg(CCXXX1_ADDR,     rfSettings.ADDR);
00172 
00173     write_reg(CCXXX1_CHANNR,   rfSettings.CHANNR);
00174     write_reg(CCXXX1_FSCTRL1,  rfSettings.FSCTRL1);
00175 //    write_reg(CCXXX1_FSCTRL0,  rfSettings.FSCTRL0);
00176     write_reg(CCXXX1_FREQ2,    rfSettings.FREQ2);
00177 
00178     write_reg(CCXXX1_FREQ1,    rfSettings.FREQ1);
00179     write_reg(CCXXX1_FREQ0,    rfSettings.FREQ0);
00180     write_reg(CCXXX1_MDMCFG4,  rfSettings.MDMCFG4);
00181     write_reg(CCXXX1_MDMCFG3,  rfSettings.MDMCFG3);
00182 
00183     write_reg(CCXXX1_MDMCFG2,  rfSettings.MDMCFG2);
00184     write_reg(CCXXX1_MDMCFG1,  rfSettings.MDMCFG1);
00185     write_reg(CCXXX1_MDMCFG0,  rfSettings.MDMCFG0);
00186     write_reg(CCXXX1_DEVIATN,  rfSettings.DEVIATN);
00187     write_reg(CCXXX1_MCSM2 ,   rfSettings.MCSM2);
00188     write_reg(CCXXX1_MCSM1 ,   rfSettings.MCSM1);
00189     write_reg(CCXXX1_MCSM0 ,   rfSettings.MCSM0 );
00190     write_reg(CCXXX1_FOCCFG,   rfSettings.FOCCFG);
00191     write_reg(CCXXX1_BSCFG,    rfSettings.BSCFG);
00192     write_reg(CCXXX1_AGCCTRL2, rfSettings.AGCCTRL2);
00193     write_reg(CCXXX1_AGCCTRL1, rfSettings.AGCCTRL1);
00194     write_reg(CCXXX1_AGCCTRL0, rfSettings.AGCCTRL0);
00195     // WOREVT1
00196     // WOREVT0
00197     // WORCTRL
00198     write_reg(CCXXX1_FREND1,   rfSettings.FREND1);
00199     write_reg(CCXXX1_FREND0,   rfSettings.FREND0);
00200     //write_reg(CCXXX1_FSCAL3,   rfSettings.FSCAL3);
00201     //write_reg(CCXXX1_FSCAL2,   rfSettings.FSCAL2);
00202     //write_reg(CCXXX1_FSCAL1,   rfSettings.FSCAL1);
00203     //write_reg(CCXXX1_FSCAL0,   rfSettings.FSCAL0);
00204     // PCCTRL1
00205     // PCCTRL0
00206     // FSTEST
00207     // PTEST
00208     // AGCTEST
00209     //write_reg(CCXXX1_TEST2,    rfSettings.TEST2);
00210     //write_reg(CCXXX1_TEST1,    rfSettings.TEST1);
00211     //write_reg(CCXXX1_TEST0,    rfSettings.TEST0);
00212 #if DEBUG_MODE > 0
00213     LOG("Configurations registers ready");
00214 #endif
00215 }
00216 
00217 
00218 void CC1101::power_on_reset(void)
00219 {
00220 #if DEBUG_MODE > 0
00221     LOG("Beginning Power-on-Reset routine...");
00222 #endif
00223 
00224     delete _spi;
00225 
00226     // make sure chip is not selected
00227     *_cs = 1;
00228 
00229     DigitalOut *SI = new DigitalOut(_mosi_pin);
00230     DigitalOut *SCK = new DigitalOut(_sck_pin);
00231     DigitalIn *SO = new DigitalIn(_miso_pin);
00232 
00233     // bring SPI lines to a defined state. Reasons are outlined in CC1101 datasheet - section 11.3
00234     *SI = 0;
00235     *SCK = 1;
00236 
00237     // toggle chip select and remain in high state afterwards
00238     toggle_cs();
00239     toggle_cs();
00240 
00241     // wait at least 40us
00242     wait_us(45);
00243 
00244     // pull CSn low & wait for the serial out line to go low
00245     *_cs = 0;
00246     while(*SO);
00247 
00248     // cleanup everything before the mbed's SPI library calls take back over
00249     delete SI;
00250     delete SO;
00251     delete SCK;
00252 
00253     // reestablish the SPI bus and call the reset strobe
00254     setup_spi();
00255     reset();
00256 
00257     delete _spi;
00258     // wait for the SO line to go low again. Once low, reset is complete and CC1101 is in IDLE state
00259     DigitalIn *SO2 = new DigitalIn(_miso_pin);
00260     while(*SO2);
00261 
00262     // make sure chip is deselected before returning
00263     *_cs = 1;
00264 
00265     // reestablish the SPI bus for the final time after removing the DigitalIn object
00266     delete SO2;
00267     setup_spi();
00268 
00269 #if DEBUG_MODE > 0
00270     LOG("CC1101 Power-on-Reset complete");
00271 #endif
00272 }
00273 
00274 // 2nd ighest level of initilization routines behind CC1101::setup();
00275 void CC1101::init(void)
00276 {
00277 
00278     power_on_reset();
00279 
00280     // Send all configuration values to the CC1101 registers
00281     put_rf_settings();
00282 
00283     uint8_t paTable[] = {0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};   // 10dB
00284     write_reg(CCXXX1_PATABLE, paTable[0]);
00285 
00286     // Flush TX and RX buffers before beginning
00287     flush_rx();
00288     flush_tx();
00289 
00290     // Set the initial offset frequency estimate
00291 
00292     LOG("Configuring frequency offset estimate...");
00293     write_reg(CCXXX1_FSCTRL0, status(CCXXX1_FREQEST));
00294     LOG("Frequency offset estimate configured");
00295 
00296     calibrate();
00297 
00298     rx_mode();
00299 }
00300 
00301 // Returns the current mode that the CC1101 is operating in
00302 uint8_t CC1101::mode(void)
00303 {
00304     return status(CCXXX1_MARCSTATE);
00305 }
00306 
00307 
00308 int32_t CC1101::sendData(uint8_t *buf, uint8_t size)
00309 {
00310     // [X] - 1 - Move all values down by 1 to make room for the packet's size value.
00311     // =================
00312     for (int i = size; i > 0; i--)
00313         buf[i] = buf[i-1];
00314 
00315 
00316     // [X] - 2 - Place the packet's size as the array's first value.
00317     // =================
00318     buf[0] = size;
00319 
00320 
00321 #if CCXXX1_DEBUG_MODE > 0
00322     LOG("PACKET TRANSMITTED\r\n  Bytes: %u", size);
00323 #endif
00324 
00325 
00326     // [X] - 3 - Send the data to the CC1101. Increment the size value by 1 before doing so to account for the buffer's inserted value
00327     // =================
00328     write_reg(CCXXX1_TXFIFO, buf, ++size);
00329 
00330 
00331 #if CCXXX1_DEBUG_MODE > 1
00332     Timer t1;
00333 #endif
00334 
00335 
00336     // [X] - 4 - Enter the TX state.
00337     // =================
00338     strobe(CCXXX1_STX);
00339 
00340 
00341 #if CCXXX1_DEBUG_MODE > 1
00342     /*  For the debug mode, this will determine how long the CC1101 takes to transmit everything in the TX buffer
00343         and enter or return to the RX state.
00344     */
00345     t1.start();
00346     float ti = t1.read();
00347 #endif
00348 
00349 
00350     // [X] - 5 - Wait until radio enters back to the RX state.
00351     // =================
00352     // *Note: Takes very few cycles, so might as well wait before returning to elimate querky errors.
00353     //while(mode() != 0x0D);
00354 
00355 #if CCXXX1_DEBUG_MODE > 1
00356     t1.stop();
00357     LOG("Time:  %02.4f ms", (t1.read() - ti)*1000);
00358 #endif
00359 
00360     // [] - 6 - Return any error codes if necessary.
00361     // =================
00362 
00363     return 0;   // success
00364 }
00365 
00366 
00367 int32_t CC1101::getData(uint8_t *buf, uint8_t *length)
00368 {
00369     // [X] - 1 - Update the frequency offset estimate.
00370     // =================
00371     write_reg(CCXXX1_FSCTRL0, status(CCXXX1_FREQEST));
00372 
00373 
00374     // [X] - 2 - Get the packet's size.
00375     // =================
00376     uint8_t rx_size;
00377     read_reg(CCXXX1_RXFIFO, &rx_size, 1);
00378 
00379 
00380     // [X] - 3 - Check if there are indeed bytes to be read.
00381     // =================
00382     if (rx_size & CCXXX1_RXFIFO_MASK) {
00383 
00384         // [X] - 3.1 - Check if the received data will fit in the provided buffer - fill the buffer if so.
00385         // =================
00386         if (rx_size <= *length) {
00387 
00388             // [X] - 3.1a - Read in received data from the CC1101 and put the contents in the provided buffer.
00389             *length = rx_size;  // set the correct length
00390             read_reg(CCXXX1_RXFIFO, buf, *length);
00391 
00392             /*  The RSSI value takes a bit to be determined by the CC1101, so having 2 separate SPI reads gives
00393                 the CC1101 enough time to determine the correct value.
00394             */
00395 
00396             // [X] - 3.1b - Read the 2 appended status bytes.
00397             // status[0] = RSSI. status[1] = LQI.
00398             uint8_t status_bytes[2];
00399             read_reg(CCXXX1_RXFIFO, status_bytes, 2);
00400 
00401             // Update the RSSI reading.
00402             rssi(status_bytes[0]);
00403             _lqi = status_bytes[1] & CCXXX1_RXFIFO_MASK; // MSB of LQI is the CRC_OK bit - The interrupt is only triggered if CRC is OK, so no need to check again.
00404 
00405 #if CCXXX1_DEBUG_MODE > 0
00406             LOG(
00407                 "PACKET RECEIVED\r\n"
00408                 "  Bytes: %u\r\n"
00409                 "  RSSI: %ddBm\r\n"
00410                 "  LQI:  %u"
00411                 , *length, _rssi, _lqi
00412             );
00413 #endif
00414 
00415             // [X] - 3.2c - Go back to the receiving state since CC1101 is configured for transitioning to IDLE on receiving a packet.
00416             rx_mode();
00417             return 0;   // success
00418         } else {
00419             *length = rx_size;
00420             flush_rx();
00421             return -2;  // passed buffer size is not large enough
00422         }
00423     }
00424 
00425     flush_rx();
00426     return -1;   // there is no new data to read
00427 }
00428 
00429 
00430 // Read Register
00431 uint8_t CC1101::read_reg(uint8_t addr)
00432 {
00433     _spi->frequency(8000000);
00434     toggle_cs();
00435     _spi->write(addr | CCXXX1_READ_SINGLE);
00436     uint8_t x = _spi->write(0);
00437     toggle_cs();
00438 
00439 #if CCXXX1_DEBUG_MODE > 1
00440     LOG("== Single Register Read ==\r\n    Address: 0x%02X\r\n    Value:   0x%02X", addr, x);
00441 #endif
00442     return x;
00443 }   // read_reg
00444 void CC1101::read_reg(uint8_t addr, uint8_t *buffer, uint8_t count)
00445 {
00446     _spi->frequency(5000000);
00447     toggle_cs();
00448     _spi->write(addr | CCXXX1_READ_BURST);
00449     for (uint8_t i = 0; i < count; i++) {
00450         buffer[i] = _spi->write(0);
00451     }
00452     toggle_cs();
00453 
00454 #if CCXXX1_DEBUG_MODE > 1
00455     LOG("== Burst Register Read ==\r\n    Address: 0x%02X\r\n    Bytes:   %u", addr, count);
00456 #endif
00457 }   // read_reg
00458 
00459 
00460 
00461 // Write Register
00462 void CC1101::write_reg(uint8_t addr, uint8_t value)
00463 {
00464     _spi->frequency(8000000);
00465     toggle_cs();
00466     _spi->write(addr);
00467     //tiny_delay();
00468     _spi->write(value);
00469     toggle_cs();
00470 
00471 #if CCXXX1_DEBUG_MODE > 1
00472     LOG("== Single Register Write ==\r\n    Address: 0x%02X\r\n    Value:   0x%02X", addr, value);
00473 #endif
00474 }   // write_reg
00475 void CC1101::write_reg(uint8_t addr, uint8_t *buffer, uint8_t count)
00476 {
00477     _spi->frequency(5000000);
00478     toggle_cs();
00479     _spi->write(addr | CCXXX1_WRITE_BURST);
00480     for (uint8_t i = 0; i < count; i++) {
00481         _spi->write(buffer[i]);
00482     }
00483     toggle_cs();
00484 
00485 #if CCXXX1_DEBUG_MODE > 1
00486     LOG("== Burst Register Write ==\r\n    Address: 0x%02X\r\n    Bytes:   %u", addr, count);
00487 #endif
00488 }   // write_reg
00489 
00490 
00491 // Strobe
00492 uint8_t CC1101::strobe(uint8_t addr)
00493 {
00494     _spi->frequency(8000000);
00495     toggle_cs();
00496     uint8_t x = _spi->write(addr);
00497     toggle_cs();
00498     return x;
00499 }   // strobe
00500 
00501 
00502 // Macro to calibrate the frequency synthesizer
00503 void CC1101::calibrate(void)
00504 {
00505 #if DEBUG_MODE > 0
00506     LOG("Calibrating frequency synthesizer");
00507 #endif
00508 
00509     idle();
00510 
00511     // Send the calibration strobe
00512     strobe(CCXXX1_SCAL);
00513 
00514     // Wait for the radio to leave the calibration step
00515     while( (mode() == 0x04) | (mode() == 0x05) );
00516 
00517     // The radio is now is IDLE mode, so go to RX mode
00518     rx_mode();
00519 
00520     // Wait for the radio to enter back into RX mode
00521     while( mode() != 0x0D );
00522 
00523 #if DEBUG_MODE > 0
00524     LOG("Frequency synthesizer calibrated");
00525 #endif
00526 }
00527 
00528 
00529 void CC1101::tiny_delay(void)
00530 {
00531     int i = 0;
00532     while(i < 4) {
00533         i++;
00534     }
00535 }
00536 
00537 void CC1101::address(uint8_t addr)
00538 {
00539     _address = addr;
00540     // NOW, WRITE THE ADDRESS TO THE CC1101
00541 }
00542 
00543 uint8_t CC1101::lqi(void)
00544 {
00545     return 0x3F - (_lqi & 0x3F);
00546 }
00547 
00548 // returns the CC1101's VERSION register that specifices what exact chip version is being used
00549 uint8_t CC1101::version(void)
00550 {
00551     return _chip_version;
00552 }
00553 
00554 void CC1101::channel(uint16_t chan)
00555 {
00556     if ( chan != _channel ) {
00557 #if DEBUG_MODE > 0
00558         LOG("Updating channel from %02u to %02u", _channel, chan);
00559 #endif
00560 
00561         _channel = chan;
00562         write_reg(CCXXX1_CHANNR, _channel);
00563 
00564 #if DEBUG_MODE > 0
00565         LOG("Channel updated: %02u", _channel);
00566 #endif
00567     }
00568 }
00569 
00570 // RSSI
00571 int16_t CC1101::rssi(void)
00572 {
00573     return _rssi;
00574 }
00575 void CC1101::rssi(uint8_t rssi_val)
00576 {
00577     int8_t temp;
00578 
00579     if (rssi_val & 0x80) {
00580         temp = (rssi_val - 256)>>1;
00581     } else {
00582         temp = rssi_val>>1; // divide by 2
00583     }
00584     _rssi = temp - 74;
00585 }   // rssi
00586 
00587 
00588 void CC1101::flush_rx(void)
00589 {
00590 #if DEBUG_MODE > 0
00591     LOG("Clearing RX buffer...");
00592 #endif
00593 
00594     // Make sure that the radio is in IDLE state before flushing the FIFO
00595     idle();
00596 
00597     // Flush RX FIFO
00598     strobe(CCXXX1_SFRX);
00599 
00600     // Enter back into a RX state
00601     rx_mode();
00602 
00603 #if DEBUG_MODE > 0
00604     LOG("RX buffer cleared");
00605 #endif
00606 }
00607 
00608 
00609 void CC1101::flush_tx(void)
00610 {
00611 #if DEBUG_MODE > 0
00612     LOG("Clearing TX buffer...");
00613 #endif
00614 
00615     // Make sure that the radio is in IDLE state before flushing the FIFO
00616     idle();
00617 
00618     // Flush TX FIFO
00619     strobe(CCXXX1_SFTX);
00620 
00621     // Enter back into a RX state
00622     rx_mode();
00623 
00624 #if DEBUG_MODE > 0
00625     LOG("TX buffer cleared");
00626 #endif
00627 }
00628 
00629 
00630 void CC1101::rx_mode(void)
00631 {
00632 #if DEBUG_MODE > 0
00633     LOG("Sending RX_MODE strobe to CC1101");
00634 #endif
00635 
00636     //strobe(CCXXX1_SIDLE);
00637     strobe(CCXXX1_SRX);
00638     //while(mode() != 0x0D);
00639 
00640 #if DEBUG_MODE > 0
00641     LOG("RX_MODE strobe sent to CC1101");
00642 #endif
00643 }
00644 
00645 
00646 void CC1101::tx_mode(void)
00647 {
00648 #if DEBUG_MODE > 0
00649     LOG("Sending TX_MODE strobe to CC1101");
00650 #endif
00651 
00652     //strobe(CCXXX1_SIDLE);
00653     strobe(CCXXX1_STX);
00654     // while(mode() != 0x13);
00655 
00656 #if DEBUG_MODE > 0
00657     LOG("TX_MODE strobe sent to CC1101");
00658 #endif
00659 }
00660 
00661 void CC1101::idle(void)
00662 {
00663 #if DEBUG_MODE > 0
00664     LOG("Sending IDLE strobe to CC1101");
00665 #endif
00666 
00667     // Send the IDLE strobe
00668     strobe(CCXXX1_SIDLE);
00669     // Wait before returning
00670     //while( mode() != 0x01);
00671 
00672 #if DEBUG_MODE > 0
00673     LOG("IDLE strobe sent to CC1101");
00674 #endif
00675 }
00676 
00677 
00678 // Status byte & status of a status register
00679 uint8_t CC1101::status(void)
00680 {
00681     return strobe(CCXXX1_SNOP);
00682 }
00683 
00684 uint8_t CC1101::status(uint8_t addr)
00685 {
00686     _spi->frequency(8000000);
00687     toggle_cs();
00688     _spi->write(addr | CCXXX1_READ_BURST);
00689     //tiny_delay();
00690     uint8_t x = _spi->write(0);
00691     toggle_cs();
00692     return x;
00693 }   // status
00694 
00695 
00696 // SET FREQUENCY
00697 void CC1101::freq(uint32_t freq)
00698 {
00699     /* calculate the value that is written to the register for settings the base frequency
00700      * that the CC1101 should use for sending/receiving over the air. Default value is equivalent
00701      * to 901.83 MHz.
00702      */
00703 
00704     // this is split into 3 bytes that are written to 3 different registers on the CC1101
00705     uint32_t reg_freq = freq/(CCXXX1_CRYSTAL_FREQUENCY>>16);
00706 
00707     rfSettings.FREQ2 = (reg_freq>>16) & 0xFF;   // high byte, bits 7..6 are always 0 for this register
00708     rfSettings.FREQ1 = (reg_freq>>8) & 0xFF;    // middle byte
00709     rfSettings.FREQ0 = reg_freq & 0xFF;         // low byte
00710 }
00711 
00712 
00713 void CC1101::datarate(uint32_t rate)
00714 {
00715     // update the baud rate class member
00716     _datarate = rate;
00717 
00718     // have to be careful with bit shifting here since it requires a large amount of shifts
00719     uint32_t shift_val = 28 - (_modem.data_rate_exp & 0x0F);
00720 
00721     // compute the register value and assign it
00722     rfSettings.MDMCFG3 = ((_datarate)/(CCXXX1_CRYSTAL_FREQUENCY>>shift_val)) - 256;
00723 }
00724 
00725 
00726 // ===============
00727 void CC1101::interface_freq(uint32_t if_freq)
00728 {
00729     // The desired IF frequency for RX. Subtracted from FS base frequency in RX.
00730     // bits 7..5 are always 0
00731     rfSettings.FSCTRL1 = (if_freq/(CCXXX1_CRYSTAL_FREQUENCY>>10)) & 0x1F;
00732     rfSettings.FSCTRL0 = 0x00;  // set the initial freq calibration to 0
00733 }
00734 // ===============
00735 void CC1101::assign_modem_params()
00736 {
00737     rfSettings.MDMCFG4 = (_modem.channel_bw_exp & 0x03)<<6 | (_modem.channel_bw & 0x03)<<4 | (_modem.data_rate_exp & 0x0F);
00738     rfSettings.MDMCFG2 = _modem.dc_filter_off_en<<7 | (_modem.mod_type & 0x07)<<4 | _modem.manchester_encode_en<<3 | (_modem.sync_mode & 0x07);
00739     rfSettings.MDMCFG1 = _modem.fec_en<<7 | (_modem.preamble_bytes & 0x07)<<4 | (_modem.channel_space_exp & 0x03);
00740 }
00741 // ===============
00742 void CC1101::assign_packet_params()
00743 {
00744     rfSettings.PCKCTRL0 = _pck_control.whitening_en<<6 | (_pck_control.format_type & 0x3)<<4 | _pck_control.crc_en<<2 | (_pck_control.length_type & 0x3);
00745     rfSettings.PCKCTRL1 = (_pck_control.preamble_thresh & 0x07)<<5 | _pck_control.autoflush_en<<3 | _pck_control.status_field_en<<2 | (_pck_control.addr_check & 0x03);
00746     rfSettings.PCKLEN = _pck_control.size;
00747 }
00748 // ===============
00749 void CC1101::assign_channel_spacing(uint32_t spacing)
00750 {
00751     // have to be careful with bit shifting here since it requires a large amount of shifts
00752     uint32_t shift_val = 18 - (_modem.channel_space_exp & 0x03);
00753 
00754     // compute the register value and assign it
00755     rfSettings.MDMCFG0 = (spacing/(CCXXX1_CRYSTAL_FREQUENCY>>shift_val)) - 256;
00756 }
00757 void CC1101::set_rf_settings(void)
00758 {
00759     // set the fields for packet controls
00760     assign_packet_params();
00761 
00762     // set the fields for the frequency limits of the modem
00763     assign_modem_params();
00764 
00765     // assign an address to the CC1101. This can be used to filter packets
00766     rfSettings.ADDR = _address;
00767 
00768     // there can be 16 different channel numbers. The bandwidth and spacing are defined in other registers
00769     rfSettings.CHANNR = _channel;
00770 
00771     // disable GDO0
00772     rfSettings.IOCFG0 = 0x2E;
00773 
00774     // setup for SPI
00775     rfSettings.IOCFG1 = 0x0C;
00776 
00777     // setup for going HIGH when packet received and CRC is ok
00778     rfSettings.IOCFG2 = 0x07;
00779 
00780     rfSettings.DEVIATN = 0x62;
00781 
00782     rfSettings.FREND1 = 0xB6;
00783     rfSettings.FREND0 = 0x10;
00784 
00785 
00786     bool RX_TIME_RSSI = false;
00787     bool RX_TIME_QUAL = false;
00788     uint8_t RX_TIME = 0x07;    // no timeout
00789     rfSettings.MCSM2 = (RX_TIME_RSSI<<4) | (RX_TIME_QUAL<<3) | (RX_TIME & 0x07);
00790 
00791 
00792     uint8_t CCA_MODE = 0x00;
00793     uint8_t RXOFF_MODE = 0x00;  // go directly to IDLE when existing RX
00794     //uint8_t RXOFF_MODE = 0x03;  // stay in RX when existing RX
00795     uint8_t TXOFF_MODE = 0x03;  // go directly to RX when existing TX
00796     // uint8_t TXOFF_MODE = 0x00;  // go directly to IDLE when existing TX
00797     rfSettings.MCSM1 = ((CCA_MODE & 0x03)<<4) | ((RXOFF_MODE & 0x03)<<2) | (TXOFF_MODE & 0x03);
00798 
00799 
00800     uint8_t FS_AUTOCAL = 0x01;  // calibrate when going from IDLE to RX or TX
00801     uint8_t PO_TIMEOUT = 0x02;
00802     bool PIN_CTRL_EN = false;
00803     bool XOSC_FORCE_ON = false;
00804     rfSettings.MCSM0 = ((FS_AUTOCAL & 0x03)<<4) | ((PO_TIMEOUT & 0x03)<<2) | (PIN_CTRL_EN<<1) | (XOSC_FORCE_ON);
00805 
00806 
00807     bool FOC_BS_CS_GATE = false;
00808     uint8_t FOC_PRE_K = 0x03;
00809     bool FOC_POST_K = true;
00810     uint8_t FOC_LIMIT = 0x01;
00811     rfSettings.FOCCFG = 0x40 | (FOC_BS_CS_GATE<<5) | ((FOC_PRE_K & 0x03)<<3) | (FOC_POST_K<<2) | (FOC_LIMIT & 0x03);
00812 
00813     rfSettings.BSCFG = 0x1C;
00814 
00815     rfSettings.AGCCTRL2 = 0xC7;
00816     rfSettings.AGCCTRL1 = 0x00;
00817     rfSettings.AGCCTRL0 = 0xB0;
00818 
00819     // rfSettings.FIFOTHR = 0x0F;   // RXFIFO and TXFIFO thresholds.
00820 
00821     // 33 byte TX FIFO & 32 byte RX FIFO
00822     rfSettings.FIFOTHR = 0x07;   // RXFIFO and TXFIFO thresholds.
00823 }