From 7e416b5c745ede5fbc4652a111b32f1e7d84058d Mon Sep 17 00:00:00 2001 From: Nathael Pajani Date: Thu, 24 Apr 2014 04:37:00 +0200 Subject: [PATCH] Add support for the CC1101 chip from TI Receiving is done by pooling Sending is done when a line has been received on UART1 and the "send" flag set. Need to implement the "packet sent/received" interrupt. --- drivers/cc1101.c | 437 +++++++++++++++++++++++++++++++++++++++ include/drivers/cc1101.h | 256 +++++++++++++++++++++++ 2 files changed, 693 insertions(+) create mode 100644 drivers/cc1101.c create mode 100644 include/drivers/cc1101.h diff --git a/drivers/cc1101.c b/drivers/cc1101.c new file mode 100644 index 0000000..b626581 --- /dev/null +++ b/drivers/cc1101.c @@ -0,0 +1,437 @@ +/**************************************************************************** + * drivers/cc1101.c + * + * Copyright 2014 Nathael Pajani + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + *************************************************************************** */ + +#include +#include "core/lpc_regs_12xx.h" +#include "core/lpc_core_cm0.h" +#include "core/system.h" +#include "core/pio.h" +#include "lib/string.h" +#include "drivers/ssp.h" +#include "drivers/cc1101.h" + + +/***************************************************************************** */ +/* CC1101 */ +/***************************************************************************** */ +struct cc1101_device { + uint8_t spi_num; + struct pio cs_pin; /* SPI CS pin, used as chip select */ + struct pio miso_pin; /* SPI MISO pin, used to monitor "device ready" from CC1101 chip */ + /* Signal indication */ + uint8_t rx_sig_strength; /* Received signal strength indication */ + uint8_t link_quality; /* link quality */ +}; +static struct cc1101_device cc1101 = { + .rx_sig_strength = 0, + .link_quality = 0, +}; + + +/***************************************************************************** */ +/* Main SPI transfer function */ +uint8_t cc1101_spi_transfer(uint8_t addr, uint8_t* out, uint8_t* in, uint8_t size) +{ + struct lpc_gpio* gpio = LPC_GPIO_REGS(cc1101.cs_pin.port); + uint8_t status = 0; + + /* Set CS Low */ + gpio->clear = (1 << cc1101.cs_pin.pin); + + /* Wait for ready state (GDO_1 / MISO going low) */ + do {} while (gpio->in & (0x01 << cc1101.miso_pin.pin)); + + /* Send address and get global status */ + status = (uint8_t)spi_transfer_single_frame(cc1101.spi_num, (uint16_t)addr); + /* Perform transfer */ + if (size != 0) { + spi_transfer_multiple_frames(cc1101.spi_num, out, in, size, 8); + } + + /* Wait for 20ns before pulling CS back high ... 20ns is one nop() at 50MHz */ + gpio->set = (1 << cc1101.cs_pin.pin); + + return status; +} + + +/***************************************************************************** */ +/* SPI registers and commands access Wrappers */ + +/* Send command and return global status byte */ +uint8_t cc1101_send_cmd(uint8_t addr) +{ + return cc1101_spi_transfer((addr | CC1101_WRITE_OFFSET), NULL, NULL, 0); +} +void cc1101_reset(void) +{ + cc1101_send_cmd(CC1101_CMD(reset)); +} +void cc1101_power_up_reset(void) __attribute__ ((alias ("cc1101_reset"))); + +void cc1101_flush_tx_fifo(void) +{ + /* Make sure that the radio is in IDLE state before flushing the FIFO */ + cc1101_send_cmd(CC1101_CMD(state_idle)); + cc1101_send_cmd(CC1101_CMD(flush_tx)); +} +void cc1101_flush_rx_fifo(void) +{ + /* Make sure that the radio is in IDLE state before flushing the FIFO */ + cc1101_send_cmd(CC1101_CMD(state_idle)); + cc1101_send_cmd(CC1101_CMD(flush_rx)); +} + +void cc1101_enter_rx_mode(void) +{ + cc1101_send_cmd(CC1101_CMD(state_idle)); + cc1101_send_cmd(CC1101_CMD(state_rx)); +} + +static uint8_t cc1101_enter_tx_mode(void) +{ + uint8_t status = 0; + status = (cc1101_read_status() & CC1101_STATE_MASK); + if (status != CC1101_STATE_TX) { + cc1101_send_cmd(CC1101_CMD(state_idle)); + cc1101_send_cmd(CC1101_CMD(state_tx)); + } + /* Wait until chip is in Tx state */ + do { + status = (cc1101_read_status() & CC1101_STATE_MASK); + if (status == CC1101_STATE_TXFIFO_UNDERFLOW) { + cc1101_flush_tx_fifo(); + return status; + } + if (status == CC1101_STATE_RXFIFO_OVERFLOW) { + cc1101_flush_rx_fifo(); + return status; + } + } while (status != CC1101_STATE_TX); + return 0; +} + +/* Read global status byte */ +uint8_t cc1101_read_status(void) +{ + return cc1101_send_cmd(CC1101_CMD(no_op)); +} + +/* Read and return single register value */ +uint8_t cc1101_read_reg(uint8_t addr) +{ + uint8_t ret = 0; + cc1101_spi_transfer((addr | CC1101_READ_OFFSET), NULL, &ret, 1); + return ret; +} +/* Read nb registers from start_addr into buffer. Return the global status byte. */ +uint8_t cc1101_read_burst_reg(uint8_t start_addr, uint8_t* buffer, uint8_t nb) +{ + uint8_t addr = (start_addr | CC1101_READ_OFFSET | CC1101_BURST_MODE); + return cc1101_spi_transfer(addr, NULL, buffer, nb); +} +/* Write single register value. Return the global status byte */ +uint8_t cc1101_write_reg(uint8_t addr, uint8_t val) +{ + return cc1101_spi_transfer((addr | CC1101_WRITE_OFFSET), &val, NULL, 1); +} +uint8_t cc1101_write_burst_reg(uint8_t start_addr, uint8_t* buffer, uint8_t nb) +{ + uint8_t addr = (start_addr | CC1101_WRITE_OFFSET | CC1101_BURST_MODE); + return cc1101_spi_transfer(addr, buffer, NULL, nb); +} + + + +/***************************************************************************** */ +/* Signal strength and link quality */ + +/* Return the signal strength indication based in the last packet received */ +uint8_t cc1101_get_signal_strength_indication(void) +{ + uint8_t val = cc1101.rx_sig_strength; + if (val >= 128) { + val = 255 - val; + } + return (val >> 1) + 74; /* val/2 + 74 */ +} +/* Return the link quality indication based in the last packet received */ +uint8_t cc1101_get_link_quality(void) +{ + return (0x3F - (cc1101.link_quality & 0x3F)); +} + + +/***************************************************************************** */ +/* Rx fifo state : + * Return 0 when fifo is empty, or number of remaining bytes when non empty and no + * overflow occured. + * Return -1 when an overflow occured. + * Upon overflow, the radio is placed in idle state and the RX fifo flushed. + * Else the radio is placed in RX state. + */ +int cc1101_rx_fifo_state(void) +{ + uint8_t rx_status = 0; + + cc1101_send_cmd(CC1101_CMD(state_rx)); + rx_status = cc1101_read_reg(CC1101_STATUS(rx_bytes)); + + /* Check for buffer overflow */ + if (rx_status & CC1101_RX_FIFO_OVERFLOW) { + cc1101_flush_rx_fifo(); + return -1; + } + return rx_status; +} + +/* Tx fifo state : + * Return 0 when fifo is empty, or number of remaining bytes when non empty and no + * overflow occured. + * Return a negative value on error: + * when an underflow occured, return value is -1 + * on other errors return value is (-1) * (global status byte) + * Upon error, the radio is placed in idle state and the TX fifo flushed. + * Else the radio is placed in TX state. + */ +int cc1101_tx_fifo_state(void) +{ + uint8_t tx_status = 0, ret = 0; + + ret = cc1101_enter_tx_mode(); + if (ret != 0) { + return -ret; + } + tx_status = cc1101_read_reg(CC1101_STATUS(tx_bytes)); + + /* Check for buffer */ + if (tx_status & CC1101_TX_FIFO_UNDERFLOW) { + cc1101_flush_tx_fifo(); + return -1; + } + return tx_status; +} + +/***************************************************************************** */ +/* Send packet + * When using a packet oriented communication with packet size and address included + * in the packet, these must be included in the packet by the software before + * calling this function. + * In order to send packets of more than 64 bytes (including length and address) the + * user will have to write his own function. + */ +int cc1101_send_packet(uint8_t* buffer, uint8_t size) +{ + uint8_t ret = 0; + if (size > CC1101_FIFO_SIZE) { + return -E2BIG; + } + cc1101_write_burst_reg(CC1101_FIFO_BURST, buffer, size); + ret = cc1101_enter_tx_mode(); + if (ret != 0) { + return -ret; + } + return size; +} + +/* Receive packet + * This function can be used to receive a packet of variable packet length (first byte + * in the packet must be the length byte). The packet length should not exceed + * the RX FIFO size. + * The buffer provided must be able to hold "size" bytes from the receive fifo. + * Returns the size filled in the buffer if everything went right. + * Returns a negative value upon error. + * CC1101_ERR_RCV_PKT_TOO_BIG: Received packet said to be bigger than fifo size + * CC1101_ERR_BUFF_TOO_SMALL: Provided buffer is smaller than received packet + * CC1101_ERR_INCOMPLET_PACKET: Fifo hodls less data than received packet length + * CC1101_OVERFLOW: RX fifo overflow + * CC1101_ERR_CRC: Packet CRC error. The fifo has been flushed. + * In every case we read as many data as possible, which is the provided buffer + * size in case of CC1101_ERR_BUFF_TOO_SMALL. In other cases, it is the maximum + * possible depending on available bytes in fifo (status provides this), the + * buffer size, and the packet size (provided in buffer[0]). + */ +int cc1101_receive_packet(uint8_t* buffer, uint8_t size, uint8_t* status) +{ + uint8_t rx_status = 0; + uint8_t read_size = 0, pkt_length = 0; + int ret = 0; + uint8_t st_buff[2]; + + /* Get fifo state */ + rx_status = cc1101_read_reg(CC1101_STATUS(rx_bytes)); + *status = rx_status; + + /* Empty fifo ? */ + if (rx_status == 0) { + return 0; + } + /* Receive one packet at most */ + pkt_length = cc1101_read_reg(CC1101_FIFO); + if (pkt_length > (CC1101_FIFO_SIZE - 1)) { + ret = -CC1101_ERR_RCV_PKT_TOO_BIG; + if (size < (rx_status & CC1101_BYTES_IN_FIFO_MASK)) { + read_size = size; + } else { + read_size = (rx_status & CC1101_BYTES_IN_FIFO_MASK); + } + } else if ((pkt_length + 1) > size) { + ret = -CC1101_ERR_BUFF_TOO_SMALL; + read_size = size; + } else if (pkt_length > (rx_status & CC1101_BYTES_IN_FIFO_MASK)) { + ret = -CC1101_ERR_INCOMPLET_PACKET; + read_size = (rx_status & CC1101_BYTES_IN_FIFO_MASK); + } else { + ret = pkt_length + 1; + read_size = pkt_length + 1; + } + /* Fill the buffer ! */ + buffer[0] = pkt_length; + read_size--; + cc1101_read_burst_reg(CC1101_FIFO_BURST, &(buffer[1]), read_size); + + /* Update the link quality and signal strength information */ + cc1101_read_burst_reg(CC1101_FIFO_BURST, st_buff, 2); + cc1101.link_quality = st_buff[1]; + cc1101.rx_sig_strength = st_buff[0]; + + /* CRC error */ + if (!(cc1101.link_quality & CC1101_CRC_OK)) { + cc1101_flush_rx_fifo(); + return -CC1101_ERR_CRC; + } + /* Overflow ? */ + if (rx_status & CC1101_RX_FIFO_OVERFLOW) { + cc1101_flush_rx_fifo(); + return -CC1101_ERR_OVERFLOW; + } + return ret; +} + +/***************************************************************************** */ +/* CC1101 Initialisation */ + +/* Table of initial settings, in the form of address / value pairs. */ +static uint8_t rf_init_settings[] = { + CC1101_REGS(gdo_config[0]), 0x2E, /* GDO_2 - High impedance (Disabled) */ + CC1101_REGS(gdo_config[1]), 0x29, /* GDO_1 - Chip ready | Low drive strength */ + CC1101_REGS(gdo_config[2]), 0x06, /* GDO_0 - Packet sent/received | Disable temp sensor */ + + /* RX FIFO and TX FIFO thresholds - 0x03 - FIFOTHR */ + CC1101_REGS(fifo_thresholds), 0x07, /* Bytes in TX FIFO:33 - Bytes in RX FIFO:32 */ + /* Packet length - 0x06 - PKTLEN */ + CC1101_REGS(packet_length), 0x3F, /* Max packet length of 63 bytes */ + + /* Packet automation control - 0x07 .. 0x08 - PKTCTRL1..0 */ + CC1101_REGS(pkt_ctrl[0]), 0x07, /* Accept all sync, No CRC auto flush, Append, Addr check and Bcast */ + CC1101_REGS(pkt_ctrl[1]), 0x05, /* No data Whitening, Use fifos, CRC check, Variable pkt length */ + + /* Device address - 0x09 - ADDR */ + CC1101_REGS(device_addr), 0x00, /* 0x00 and 0xFF are broadcast */ + /* Channel number - 0x0A - CHANNR */ + CC1101_REGS(channel_number), 0x00, /* Channel 0 */ + + /* Frequency synthesizer control - 0x0B .. 0x0C - FSCTRL1..0 */ + CC1101_REGS(freq_synth_ctrl[0]), 0x0C, /* Used for ?? IF: 304.6875 KHz */ + + /* Carrier Frequency control - FREQ2..0 : Fcarrier == 867.999939 MHz */ + CC1101_REGS(freq_control[0]), 0x21, /* 0x216276 == Fcarrier * 2^16 / Fxtal */ + CC1101_REGS(freq_control[1]), 0x62, /* == approx(868 MHz) * 65536 / 26 MHz */ + CC1101_REGS(freq_control[2]), 0x76, + + /* Modem configuration - MDMCFG4..0 */ + /* MDMCFG4..3 : RX filterbandwidth = 541.666667 kHz and Datarate = 249.938965 kBaud */ + CC1101_REGS(modem_config[0]), 0x2D, + CC1101_REGS(modem_config[1]), 0x3B, + /* MDMCFG2 : 30/32 sync word bits + sensitivity, Manchester disabled, GFSK, Digital DC filter enabled */ + CC1101_REGS(modem_config[2]), 0x13, + /* MDMCFG1..0 : FEC disabled, 4 preamble bytes, Channel spacing = 199.951172 kHz */ + CC1101_REGS(modem_config[3]), 0x22, + CC1101_REGS(modem_config[4]), 0xF8, + /* Modem deviation : DEVIATN */ + CC1101_REGS(modem_deviation), 0x62, /* Deviation = 127 kHz */ + + /* Front End Rx/Tx config : use defaults */ +// CC1101_REGS(front_end_rx_cfg), 0x56, +// CC1101_REGS(front_end_tx_cfg), 0x10, + + /* Main Radio Control State Machine Configuration - MCSM2..0 */ + CC1101_REGS(radio_stm[1]), 0x3F, /* CCA mode if RSSI below threshold, Stay in RX, Go to RX */ + CC1101_REGS(radio_stm[2]), 0x18, /* PO timeout 149-155us, Auto calibrate from idle to rx/tx */ + + /* Frequency Offset Compensation configuration - FOCCFG */ + CC1101_REGS(freq_offset_comp), 0x1D, /* 4K before, K/2 after, BWchan/8 */ + CC1101_REGS(bit_sync), 0x1C, /* 1*Ki, 2*Kp, Ki/2, Kp, +0 (no data rate compensation) */ + + /* AGC control - 0x1B .. 0x1D - AGCCTRL2..0 */ + CC1101_REGS(agc_ctrl[0]), 0xC7, /* Don't use 3highest gain, Max LNA gain, 42dB amp from chan filter */ + CC1101_REGS(agc_ctrl[1]), 0x00, /* LNA 2 gain decr first, Carrier sense relative threshold disabled */ + CC1101_REGS(agc_ctrl[2]), 0xB0, /* Medium settings, 24 samples wait time, normal op. */ + + /* Frequency synthesizer calibration - 0x23 .. 0x26 - FSCAL3..0 */ + CC1101_REGS(freq_synth_cal[0]), 0xEA, + CC1101_REGS(freq_synth_cal[1]), 0x2A, + CC1101_REGS(freq_synth_cal[2]), 0x00, + CC1101_REGS(freq_synth_cal[3]), 0x1F, + /* Frequency synthesizer calibration control - 0x29 - FSTEST */ + CC1101_REGS(freq_synth_cal_ctrl), 0x59, + + /* Various test settings - 0x2C .. 0x2E - TEST2..0 */ +// CC1101_REGS(test[0]), 0x88, +// CC1101_REGS(test[1]), 0x31, + CC1101_REGS(test[2]), 0x09, /* Disable VCO selection calibration stage */ +}; + +static uint8_t paTable[] = {0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; + + +/* Configure pins, reset the CC1101, and put the CC1101 chip in idle state */ +void cc1101_init(uint8_t ssp_num, struct pio* cs_pin, struct pio* miso_pin) +{ + struct lpc_gpio* gpio = LPC_GPIO_REGS(cc1101.cs_pin.port);; + + cc1101.spi_num = ssp_num; + /* Copy CS pin info and configure pin as GPIO output */ + pio_copy(&(cc1101.cs_pin), cs_pin); + /* Configure CS as output and set high */ + gpio->data_dir |= (1 << cc1101.cs_pin.pin); + gpio->set = (1 << cc1101.cs_pin.pin); + + /* Copy MISO pin info (no config, should be already configured as SPI) */ + pio_copy(&(cc1101.miso_pin), miso_pin); + + cc1101_power_up_reset(); + cc1101_send_cmd(CC1101_CMD(state_idle)); +} + +/* Write / send all the configuration register values to the CC1101 chip */ +void cc1101_config(void) +{ + int i = 0; + cc1101_send_cmd(CC1101_CMD(state_idle)); + /* Write RF initial settings to CC1101 */ + for (i = 0; i < sizeof(rf_init_settings); i += 2) { + cc1101_write_reg(rf_init_settings[i], rf_init_settings[i + 1]); + } + /* Write PA Table value */ + cc1101_write_reg(CC1101_PATABLE, paTable[0]); +} + + diff --git a/include/drivers/cc1101.h b/include/drivers/cc1101.h new file mode 100644 index 0000000..8b869f1 --- /dev/null +++ b/include/drivers/cc1101.h @@ -0,0 +1,256 @@ +/** + * @author Athanassios Mavrogeorgiadis + * @author TI CC1101 library developed by Athanassios Mavrogeorgiadis (tmav Electronics) as template based on TI C8051 SOURCE CODE swrc021f + * @section LICENSE + * + * Copyright (c) 2010 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * @section DESCRIPTION + * + * CC1101 Low-Power Sub-1 GHz RF Transceiver CC1101. + * + * Datasheet: + * + * http://focus.ti.com/lit/ds/swrs061f/swrs061f.pdf + */ + +#ifndef DRIVERS_CC1101_H +#define DRIVERS_CC1101_H + +#include "lib/stddef.h" + +/******************************************************************************/ +/* Control registers */ + +struct cc1101_configuration { + uint8_t gdo_config[3]; /* 0x00 .. 0x02 - IOCFG2 .. IOCFG0 - GDOx output pin configuration */ + uint8_t fifo_thresholds; /* 0x03 - FIFOTHR - RX FIFO and TX FIFO thresholds */ + uint8_t sync_word[2]; /* 0x04 .. 0x05 - SYNC1 .. SYNC0 - Sync word */ + uint8_t packet_length; /* 0x06 - PKTLEN - Packet length */ + uint8_t pkt_ctrl[2]; /* 0x07 .. 0x08 - PKTCTRL1 .. PKTCTRL0 - Packet automation control */ + uint8_t device_addr; /* 0x09 - ADDR - Device address */ + uint8_t channel_number; /* 0x0A - CHANNR - Channel number */ + uint8_t freq_synth_ctrl[2]; /* 0x0B .. 0x0C - FSCTRL1 .. FSCTRL0 - Frequency synthesizer control */ + uint8_t freq_control[3]; /* 0x0D .. 0x0F - FREQ2 .. FREQ0 - Frequency control word*/ + uint8_t modem_config[5]; /* 0x10 .. 0x14 - MDMCFG4 .. MDMCFG0 - Modem configuration */ + uint8_t modem_deviation; /* 0x15 - DEVIATN - Modem deviation setting */ + uint8_t radio_stm[3]; /* 0x16 .. 0x18 - MCSM2 .. MCSM0 - Main Radio Control State Machine configuration */ + uint8_t freq_offset_comp; /* 0x19 - FOCCFG - Frequency Offset Compensation configuration */ + uint8_t bit_sync; /* 0x1A - BSCFG - Bit Synchronization configuration */ + uint8_t agc_ctrl[3]; /* 0x1B .. 0x1D - AGCCTRL2 .. AGCCTRL0 - AGC control */ + uint8_t worevt_timeout[2]; /* 0x1E .. 0x1F - WOREVT1 .. WOREVT0 - Wake On Radio Event 0 timeout */ + uint8_t wake_on_radio; /* 0x20 - WORCTRL - Wake On Radio control */ + uint8_t front_end_rx_cfg; /* 0x21 - FREND1 - Front end RX configuration */ + uint8_t front_end_tx_cfg; /* 0x22 - FREND0 - Front end TX configuration */ + uint8_t freq_synth_cal[4]; /* 0x23 .. 0x26 - FSCAL3 .. FSCAL0 - Frequency synthesizer calibration */ + uint8_t rc_osc_cal[2]; /* 0x27 .. 0x28 - RCCTRL1 .. RCCTRL0 - RC oscillator configuration */ + uint8_t freq_synth_cal_ctrl; /* 0x29 - FSTEST - Frequency synthesizer calibration control */ + uint8_t production_test; /* 0x2A - PTEST - Production test */ + uint8_t agc_test; /* 0x2B - AGCTEST - AGC test */ + uint8_t test[3]; /* 0x2C .. 0x2E - TEST2 .. TEST0 - Various test settings */ + uint8_t unused_0; /* 0x2F - empty */ + uint8_t unused_1[14]; + uint8_t pa_table; /* 0x3E - PATABLE - */ + uint8_t fifo; /* 0x3F - RX / TX FIFO - */ +} __attribute__((packed)); +#define CC1101_REGS(x) (((uint8_t)offsetof(struct cc1101_configuration, x)) + (0x00)) +#define CC1101_PATABLE CC1101_REGS(pa_table) +#define CC1101_FIFO CC1101_REGS(fifo) + +#define CC1101_REGS_BURST(x) (((uint8_t)offsetof(struct cc1101_configuration, x)) + (0x40)) +#define CC1101_FIFO_BURST CC1101_REGS_BURST(fifo) + +#define CC1101_READ_OFFSET 0x80 +#define CC1101_WRITE_OFFSET 0x00 +#define CC1101_BURST_MODE 0x40 + +struct cc1101_status_regs { + uint8_t part_number; /* 0x30 - PARTNUM - Part number for CC1101 */ + uint8_t version; /* 0x31 - VERSION - Current version number */ + uint8_t freq_test; /* 0x32 - FREQEST - Frequency Offset Estimate */ + uint8_t link_quality; /* 0x33 - LQI - Demodulator estimate for Link Quality */ + uint8_t sig_strength; /* 0x34 - RSSI - Received signal strength indication */ + uint8_t state_machine; /* 0x35 - MARCSTATE - Control state machine state */ + uint8_t wor_timer[2]; /* 0x36 .. 0x37 - WORTIME1 .. WORTIME0 - WOR timer */ + uint8_t packet_status; /* 0x38 - PKTSTATUS - Current GDOx status and packet status */ + uint8_t pll_calibration; /* 0x39 - VCO_VC_DAC - Current setting from PLL calibration module */ + uint8_t tx_bytes; /* 0x3A - TXBYTES - Underflow and number of bytes in the TX FIFO */ + uint8_t rx_bytes; /* 0x3B - RXBYTES - Overrflow and number of bytes in the TX FIFO */ + uint8_t rc_calib_status[2]; /* 0x3C .. 0x3D - RCCTRL1_STATUS .. RCCTRL0_STATUS - Last RC oscillator calibration result */ +} __attribute__((packed)); +#define CC1101_STATUS(x) (((uint8_t)offsetof(struct cc1101_status_regs, x)) + (0x70)) + + +struct cc1101_command_strobes { + uint8_t reset; /* 0x30 - SRES - Reset chip. */ + uint8_t start_freq_synth; /* 0x31 - SFSTXON - Enable and calibrate frequency synthesizer (if MCSM0.FS_AUTOCAL=1). If in + RX/TX: Go to a wait state where only the synthesizer is running (for quick RX / TX turnaround). */ + uint8_t crystal_off; /* 0x32 - SXOFF - Turn off crystal oscillator. */ + uint8_t synth_calibration; /* 0x33 - SCAL - Calibrate frequency synthesizer and turn it off (enables quick start). */ + uint8_t state_rx; /* 0x34 - SRX - Enable RX. Perform calibration first if coming from IDLE and MCSM0.FS_AUTOCAL=1. */ + uint8_t state_tx; /* 0x35 - STX - In IDLE state: Enable TX. Perform calibration first if MCSM0.FS_AUTOCAL=1. If in RX state + and CCA is enabled: Only go to TX if channel is clear. */ + uint8_t state_idle; /* 0x36 - SIDLE - Exit RX / TX, turn off frequency synthesizer and exit Wake-On-Radio mode if applicable. */ + uint8_t freq_adj; /* 0x37 - SAFC - Perform AFC adjustment of the frequency synthesizer */ + uint8_t state_wake_on_radio; /* 0x38 - SWOR - Start automatic RX polling sequence (Wake-on-Radio) */ + uint8_t state_power_down; /* 0x39 - SPWD - Enter power down mode when CSn goes high. */ + uint8_t flush_rx; /* 0x3A - SFRX - Flush the RX FIFO buffer. */ + uint8_t flush_tx; /* 0x3B - SFTX - Flush the TX FIFO buffer. */ + uint8_t wor_reset; /* 0x3C - SWORRST - Reset real time clock. */ + uint8_t no_op; /* 0x3D - SNOP - No operation. May be used to pad strobe commands to two bytes for simpler software. */ +} __attribute__((packed)); +#define CC1101_CMD(x) (((uint8_t)offsetof(struct cc1101_command_strobes, x)) + (0x30)) + + +#define CC1101_RX_FIFO_OVERFLOW (0x80) +#define CC1101_TX_FIFO_UNDERFLOW (0x80) +#define CC1101_BYTES_IN_FIFO_MASK (0x7F) +#define CC1101_FIFO_SIZE 64 + +#define CC1101_CRC_OK 0x80 + + +/* Errors definitions */ +#define CC1101_ERR_BASE 10 /* Random number .... */ +#define CC1101_ERR_RCV_PKT_TOO_BIG (CC1101_ERR_BASE + 1) +#define CC1101_ERR_BUFF_TOO_SMALL (CC1101_ERR_BASE + 2) +#define CC1101_ERR_INCOMPLET_PACKET (CC1101_ERR_BASE + 3) +#define CC1101_ERR_OVERFLOW (CC1101_ERR_BASE + 4) +#define CC1101_ERR_CRC (CC1101_ERR_BASE + 5) + + +/* Definitions for chip status */ +#define CC1101_RDY 0x80 +#define CC1101_STATE_MASK 0x70 +#define CC1101_STATE_IDLE 0x00 +#define CC1101_STATE_RX 0x10 +#define CC1101_STATE_TX 0x20 +#define CC1101_STATE_FSTON 0x30 +#define CC1101_STATE_CALIBRATE 0x40 +#define CC1101_STATE_SETTLING 0x50 +#define CC1101_STATE_RXFIFO_OVERFLOW 0x60 +#define CC1101_STATE_TXFIFO_UNDERFLOW 0x70 +#define CC1101_STATE_FIFO_BYTES_MASK 0x0F + + + +/***************************************************************************** */ +/* SPI registers and commands access Wrappers */ + +/* Send command and return global status byte */ +uint8_t cc1101_send_cmd(uint8_t addr); +void cc1101_reset(void); +/* Power Up Reset is the same as a usual reset, the function will only wait longer for + * the "chip ready" signal before starting SPI transfers .... */ +void cc1101_power_up_reset(void); + +void cc1101_flush_tx_fifo(void); +void cc1101_flush_rx_fifo(void); + +void cc1101_enter_rx_mode(void); + +/* Read global status byte */ +uint8_t cc1101_read_status(void); + +/* Read and return single register value */ +uint8_t cc1101_read_reg(uint8_t addr); +/* Read nb registers from start_addr into buffer. Return the global status byte. */ +uint8_t cc1101_read_burst_reg(uint8_t start_addr, uint8_t* buffer, uint8_t nb); + +/* Write single register value. Return the global status byte */ +uint8_t cc1101_write_reg(uint8_t addr, uint8_t val); +uint8_t cc1101_write_burst_reg(uint8_t start_addr, uint8_t* buffer, uint8_t nb); + + + +/***************************************************************************** */ +/* Signal strength and link quality */ + +/* Return the signal strength indication based in the last packet received */ +uint8_t cc1101_get_signal_strength_indication(void); +/* Return the link quality indication based in the last packet received */ +uint8_t cc1101_get_link_quality(void); + + +/***************************************************************************** */ +/* Rx fifo state : + * Return 0 when fifo is empty, or number of remaining bytes when non empty and no + * overflow occured. + * Return -1 when an overflow occured. + * Upon overflow, the radio is placed in idle state and the RX fifo flushed. + * Else the radio is placed in RX state. + */ +int cc1101_rx_fifo_state(void); + +/* Tx fifo state : + * Return 0 when fifo is empty, or number of remaining bytes when non empty and no + * overflow occured. + * Return a negative value on error: + * when an underflow occured, return value is -1 + * on other errors return value is (-1) * (global status byte) + * Upon error, the radio is placed in idle state and the TX fifo flushed. + * Else the radio is placed in TX state. + */ +int cc1101_tx_fifo_state(void); + + +/***************************************************************************** */ +/* Send packet + * When using a packet oriented communication with packet size and address included + * in the packet, these must be included in the packet by the software before + * calling this function. + * In order to send packets of more than 64 bytes (including length and address) the + * user will have to write his own function. + */ +int cc1101_send_packet(uint8_t* buffer, uint8_t size); + +/* Receive packet + * This function can be used to receive a packet of variable packet length (first byte + * in the packet must be the length byte). The packet length should not exceed + * the RX FIFO size. + * The buffer provided must be able to hold "size" bytes from the receive fifo. + * Returns the size filled in the buffer if everything went right. + * Returns a negative value upon error. + * CC1101_ERR_RCV_PKT_TOO_BIG: Received packet said to be bigger than fifo size + * CC1101_ERR_BUFF_TOO_SMALL: Provided buffer is smaller than received packet + * CC1101_ERR_INCOMPLET_PACKET: Fifo hodls less data than received packet length + * CC1101_OVERFLOW: RX fifo overflow + * CC1101_ERR_CRC: Packet CRC error. The fifo has been flushed. + * In every case we read as many data as possible, which is the provided buffer + * size in case of CC1101_ERR_BUFF_TOO_SMALL. In other cases, it is the maximum + * possible depending on available bytes in fifo (status provides this), the + * buffer size, and the packet size (provided in buffer[0]). + */ +int cc1101_receive_packet(uint8_t* buffer, uint8_t size, uint8_t* status); + + + +/***************************************************************************** */ +/* CC1101 Initialisation */ + +/* Configure pins, reset the CC1101, and put the CC1101 chip in idle state */ +void cc1101_init(uint8_t ssp_num, struct pio* cs_pin, struct pio* miso_pin); + +/* Write / send all the configuration register values to the CC1101 chip */ +void cc1101_config(void); + + +#endif /* DRIVERS_CC1101_H */ -- 2.43.0