Separate internal LPC drivers and external ones Place the external ones in extdrv...
authorNathael Pajani <nathael.pajani@ed3l.fr>
Sat, 6 Dec 2014 01:51:20 +0000 (02:51 +0100)
committerNathael Pajani <nathael.pajani@ed3l.fr>
Tue, 8 Nov 2022 16:03:04 +0000 (17:03 +0100)
16 files changed:
drivers/cc1101.c [deleted file]
drivers/eeprom.c [deleted file]
drivers/status_led.c [deleted file]
drivers/tmp101_temp_sensor.c [deleted file]
extdrv/cc1101.c [new file with mode: 0644]
extdrv/eeprom.c [new file with mode: 0644]
extdrv/status_led.c [new file with mode: 0644]
extdrv/tmp101_temp_sensor.c [new file with mode: 0644]
include/drivers/cc1101.h [deleted file]
include/drivers/i2c.h
include/drivers/status_led.h [deleted file]
include/drivers/tmp101_temp_sensor.h [deleted file]
include/extdrv/cc1101.h [new file with mode: 0644]
include/extdrv/eeprom.h [new file with mode: 0644]
include/extdrv/status_led.h [new file with mode: 0644]
include/extdrv/tmp101_temp_sensor.h [new file with mode: 0644]

diff --git a/drivers/cc1101.c b/drivers/cc1101.c
deleted file mode 100644 (file)
index c49b7e4..0000000
+++ /dev/null
@@ -1,465 +0,0 @@
-/****************************************************************************
- *  drivers/cc1101.c
- *
- * Copyright 2014 Nathael Pajani <nathael.pajani@ed3l.fr>
- *
- * 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 <http://www.gnu.org/licenses/>.
- *
- *************************************************************************** */
-
-#include <stdint.h>
-#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);
-       }
-       /* Release Chip select */
-       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));
-       if (status != NULL) {
-               *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 */
-
-
-/* Change the CC1101 address
- * Only packets addressed to the specified address (or broadcasted) will be
-*    received.
- * Adresses 0x00 and 0xFF are broadcast
- * This function places the CC1101 chip in idle state.
- */
-void cc1101_set_address(uint8_t address)
-{
-       cc1101_send_cmd(CC1101_CMD(state_idle));
-       cc1101_write_reg(CC1101_REGS(device_addr), address);
-}
-
-/* Change a configuration byte.
- * This function places the CC1101 chip in idle state.
- */
-void cc1101_set_config(uint8_t byte_addr, uint8_t value)
-{
-       cc1101_send_cmd(CC1101_CMD(state_idle));
-       cc1101_write_reg(byte_addr, value);
-}
-
-/* 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]), 0x07, /* GDO_0 - Assert on CRC OK | 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 = NULL;
-
-       if ((cs_pin == NULL) || (miso_pin == NULL)) {
-               return;
-       }
-       gpio = LPC_GPIO_REGS(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/drivers/eeprom.c b/drivers/eeprom.c
deleted file mode 100644 (file)
index 8a0f8c1..0000000
+++ /dev/null
@@ -1,262 +0,0 @@
-/****************************************************************************
- *   drivers/eeprom.c
- *
- *
- * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
- *
- *
- * 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 <http://www.gnu.org/licenses/>.
- *
- *************************************************************************** */
-
-#include <stdint.h>
-
-#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/i2c.h"
-
-
-/***************************************************************************** */
-/*       EEPROM Chip select for the GPIO Demo module                           */
-/*******************************************************************************/
-/* Set the SPI SSEL pin low. */
-/* These functions are specific to the mod_gpio_demo and domotab modules.
- * It is used to release the gate that blocks the SCL signal to the EEPROM,
- *   allowing multiple eeproms with the same address to be accessed one at a time
- *   on the same I2C Bus, which gives a way to both identify modules presence and
- *   module function, name, and pther capabilities.
- * When the SPI is used as slave, the master has the control of the SPI SSEL signal
- *   and the EEPROM should not be accessed by the module.
- * Other I2C EEPROMs should not need these functions.
- */
-static struct pio i2c_eeprom_cs = LPC_GPIO_0_15;
-int mod_gpio_demo_eeprom_cs_pull_low(void)
-{
-    struct lpc_gpio* gpio_port_regs = LPC_GPIO_REGS(i2c_eeprom_cs.port);
-    config_pio(&i2c_eeprom_cs, (LPC_IO_MODE_PULL_UP | LPC_IO_DIGITAL));
-    /* Configure SPI_CS as output and set it low. */
-    gpio_port_regs->data_dir |= (1 << i2c_eeprom_cs.pin);
-    gpio_port_regs->clear = (1 << i2c_eeprom_cs.pin);
-       return 0;
-}
-void mod_gpio_demo_eeprom_cs_release(void)
-{
-       struct lpc_gpio* gpio_port_regs = LPC_GPIO_REGS(i2c_eeprom_cs.port);
-    gpio_port_regs->set = (1 << i2c_eeprom_cs.pin);
-}
-
-
-/***************************************************************************** */
-/*          Read and Write for module eeprom                                   */
-/***************************************************************************** */
-/* Config */
-/* Small eeprom : up to 2k bytes. These use a segment address on the lower three bits
- *   of the address byte, and thus reply on 8 consecutive addresses */
-#define EEPROM_ID_SMALL_ADDR  0xA0
-#define EEPROM_ID_SMALL_I2C_SIZE  1024
-#define EEPROM_ID_SMALL_PAGE_SIZE 16
-/* Big eeprom : from 4k bytes and above : These use two address bytes, and the three
- *   physical address pins are used to set the chip address. On DTPlug modules they should
- *   have address 0xA8. */
-#define EEPROM_ID_BIG_ADDR  0xA8
-#define EEPROM_ID_BIG_I2C_SIZE  16*1024
-#define EEPROM_ID_BIG_PAGE_SIZE 64
-
-
-
-/* Detect the eeprom size */
-int eeprom_detect(void)
-{
-       int ret = 0;
-       char cmd_buf[1] = { EEPROM_ID_SMALL_ADDR, };
-
-       /* Look for small eeproms first, only these would answer on EEPROM_ID_SMALL_ADDR */
-       ret = i2c_read(cmd_buf, 1, NULL, NULL, 0);
-       if (ret == 0) {
-               return EEPROM_TYPE_SMALL;
-       }
-       /* No small eeprom ... look for big ones */
-       cmd_buf[0] = EEPROM_ID_BIG_ADDR;
-       ret = i2c_read(cmd_buf, 1, NULL, NULL, 0);
-       if (ret == 0) {
-               return EEPROM_TYPE_BIG;
-       }
-
-       if (ret > 0) {
-               return -EIO;
-       } else if (ret == -EREMOTEIO) {
-               return EEPROM_TYPE_NONE; /* No module */
-       }
-       return ret; /* Error or module size */
-}
-
-int get_eeprom_type(void)
-{
-       static int eeprom_type = -1;
-
-       if (eeprom_type >= 0) {
-               return eeprom_type; /* No need to check again */
-       }
-
-       eeprom_type = eeprom_detect();
-       if (eeprom_type <= 0) {
-               return -1;
-       }
-       return eeprom_type;
-}
-
-
-/* EEPROM Read
- * Performs a non-blocking read on the eeprom.
- *   address : data offset in eeprom.
- * RETURN VALUE
- *   Upon successfull completion, returns the number of bytes read. On error, returns a negative
- *   integer equivalent to errors from glibc.
- *   -EFAULT : address above eeprom size
- *   -EBADFD : Device not initialized
- *   -EBUSY : Device or ressource Busy or Arbitration lost
- *   -EAGAIN : Device already in use
- *   -EINVAL : Invalid argument (buf)
- *   -EREMOTEIO : Device did not acknowledge
- *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
- */
-#define CMD_BUF_SIZE 4
-int eeprom_read(uint32_t offset, void *buf, size_t count)
-{
-       int ret = 0;
-       char cmd_buf[CMD_BUF_SIZE] = { EEPROM_ID_BIG_ADDR, 0, 0, (EEPROM_ID_BIG_ADDR | 0x01), };
-       char ctrl_buf[CMD_BUF_SIZE] = { I2C_CONT, I2C_CONT, I2C_DO_REPEATED_START, I2C_CONT, };
-       int eeprom_type = 0;
-
-       if (mod_gpio_demo_eeprom_cs_pull_low() != 0) {
-               return -EBUSY;
-       }
-       eeprom_type = get_eeprom_type();
-
-       /* Read the requested data */
-       switch (eeprom_type) {
-               case EEPROM_TYPE_SMALL:
-                       cmd_buf[0] = EEPROM_ID_SMALL_ADDR | ((offset & 0x700) >> 7);
-                       cmd_buf[1] = offset & 0xFF;
-                       cmd_buf[2] = EEPROM_ID_SMALL_ADDR | 0x01;
-                       ret = i2c_read(cmd_buf, CMD_BUF_SIZE - 1, ctrl_buf + 1, buf, count);
-                       break;
-               case EEPROM_TYPE_BIG:
-                       cmd_buf[1] = ((offset & 0xFF00) >> 8);
-                       cmd_buf[2] = offset & 0xFF;
-                       ret = i2c_read(cmd_buf, CMD_BUF_SIZE, ctrl_buf, buf, count);
-                       break;
-               default:
-                       ret = -1;
-                       break;
-       }
-       mod_gpio_demo_eeprom_cs_release();
-
-       return ret;
-}
-
-
-/* EEPROM Write
- * Performs a non-blocking write on the eeprom.
- *   address : data offset in eeprom.
- * RETURN VALUE
- *   Upon successfull completion, returns the number of bytes written. On error, returns a negative
- *   integer equivalent to errors from glibc.
- *   -EFAULT : address above eeprom size
- *   -EBADFD : Device not initialized
- *   -EBUSY : Device or ressource Busy or Arbitration lost
- *   -EAGAIN : Device already in use
- *   -EINVAL : Invalid argument (buf)
- *   -EREMOTEIO : Device did not acknowledge
- *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
- */
-#define CMD_SIZE_SMALL 2
-#define CMD_SIZE_BIG 3
-#define MAX_CMD_SIZE CMD_SIZE_BIG
-#define EEPROM_ID_MAX_PAGE_SIZE EEPROM_ID_BIG_PAGE_SIZE
-int eeprom_write(uint32_t offset, const void *buf, size_t count)
-{
-       int ret = 0;
-       uint8_t cmd_size = CMD_SIZE_BIG, page_size = EEPROM_ID_BIG_PAGE_SIZE;
-       int write_count = 0, size = 0;
-       char cmd[MAX_CMD_SIZE] = { EEPROM_ID_BIG_ADDR, 0, 0 };
-       char full_buff[(EEPROM_ID_MAX_PAGE_SIZE + MAX_CMD_SIZE)];
-       int eeprom_type = 0;
-
-       if (mod_gpio_demo_eeprom_cs_pull_low() != 0) {
-               return -EBUSY;
-       }
-       eeprom_type = get_eeprom_type();
-
-       switch (eeprom_type) {
-               case EEPROM_TYPE_SMALL:
-                       cmd_size = CMD_SIZE_SMALL;
-                       page_size = EEPROM_ID_SMALL_PAGE_SIZE;
-                       break;
-               case EEPROM_TYPE_BIG:
-                       /* already configured */
-                       /* cmd_size = CMD_SIZE_BIG; */
-                       /* page_size = EEPROM_ID_BIG_PAGE_SIZE; */
-                       break;
-               default:
-                       ret = -1;
-                       write_count = count + 1; /* skip the while loop, but return error */
-                       break;
-       }
-       while (write_count < count) {
-               switch (eeprom_type) {
-                       case EEPROM_TYPE_SMALL:
-                               cmd[0] = EEPROM_ID_SMALL_ADDR | ((offset & 0x700) >> 7);
-                               cmd[1] = offset & 0xFF;
-                               break;
-                       case EEPROM_TYPE_BIG:
-                               cmd[1] = ((offset & 0xFF00) >> 8);
-                               cmd[2] = offset & 0xFF;
-                               break;
-               }
-               /* make partial first write to allign to page boundaries */
-               if (offset & (page_size - 1)) {
-                       size = (page_size - (offset & (page_size - 1)));
-               } else {
-                       size = page_size;
-               }
-               if (size > (count - write_count))
-                       size = (count - write_count);
-               offset += size;
-               memcpy(full_buff, cmd, cmd_size);
-               memcpy(full_buff + cmd_size, buf + write_count, size);
-               ret = i2c_write(full_buff, (cmd_size + size), NULL);
-
-               if (ret != (cmd_size + size)) {
-                       break;
-               }
-               /* Wait for page write completion : The device does not acknoledge anything during
-                * page write, perform page writes with no data, until it returns 1 */
-               do {
-                       ret = i2c_write(full_buff, 1, NULL);
-               } while (ret != 1);
-
-               write_count += size;
-       }
-       mod_gpio_demo_eeprom_cs_release();
-
-       if (write_count != count)
-               return ret;
-       return write_count;
-}
-
-
diff --git a/drivers/status_led.c b/drivers/status_led.c
deleted file mode 100644 (file)
index e499524..0000000
+++ /dev/null
@@ -1,136 +0,0 @@
-/****************************************************************************
- *  drivers/status_led.c
- *
- * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
- *
- * 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 <http://www.gnu.org/licenses/>.
- *
-*************************************************************************** */
-
-/***************************************************************************** */
-/*                Status Led                                                   */
-/***************************************************************************** */
-
-
-#include <stdint.h>
-#include "core/lpc_regs_12xx.h"
-#include "core/system.h"
-#include "core/pio.h"
-#include "drivers/status_led.h"
-
-
-/***************************************************************************** */
-/* Status LED is the bicolors red/green led on the GPIO Demo module */
-
-/* This code configures the status led and enables it's use as a debug helper
- * or visual watchdog.
- * Calls to chenillard() with a value of about 25ms or more will trigger a
- * defined sequence to be displayed by the status led.
- * This sequence implies a big delay in your code (eleven times the value used
- * as argument in ms.
- *
- * If you want to use this led in a more application friendly way (with no sleep)
- * you must use a timer to call a "stepping" routine (either systick timer or any
- * of the other four timers).
- */
-
-/* The status LED is on GPIO Port 1, pin 4 (PIO1_4) and Port 1, pin 5 (PIO1_5) */
-#define LED_RED    5
-#define LED_GREEN  4
-
-void status_led_config(void)
-{
-       struct lpc_gpio* gpio1 = LPC_GPIO_REGS(1);
-       uint32_t mode = (LPC_IO_MODE_PULL_UP | LPC_IO_DIGITAL | LPC_IO_DRIVE_HIGHCURENT);
-       struct pio red_led = LPC_GPIO_1_5;
-       struct pio green_led = LPC_GPIO_1_4;
-       /* Status Led GPIO */
-       config_pio(&green_led, mode);
-       config_pio(&red_led, mode);
-       /* Configure both as output */
-       gpio1->data_dir |= (1 << LED_GREEN) | (1 << LED_RED);
-       /* Turn both LEDs on */
-       //gpio1->set = (1 << LED_GREEN) | (1 << LED_RED);
-       gpio1->set = (1 << LED_GREEN);
-}
-
-void status_led(uint32_t val)
-{
-       struct lpc_gpio* gpio1 = LPC_GPIO_REGS(1);
-
-       switch (val) {
-               case red_only:
-                       gpio1->set = (1 << LED_RED);
-                       gpio1->clear = (1 << LED_GREEN);
-                       break;
-               case red_on:
-                       gpio1->set = (1 << LED_RED);
-                       break;
-               case red_off:
-                       gpio1->clear = (1 << LED_RED);
-                       break;
-               case red_toggle:
-                       gpio1->toggle = (1 << LED_RED);
-                       break;
-               case green_only:
-                       gpio1->set = (1 << LED_GREEN);
-                       gpio1->clear = (1 << LED_RED);
-                       break;
-               case green_on:
-                       gpio1->set = (1 << LED_GREEN);
-                       break;
-               case green_off:
-                       gpio1->clear = (1 << LED_GREEN);
-                       break;
-               case green_toggle:
-                       gpio1->toggle = (1 << LED_GREEN);
-                       break;
-               case both:
-                       gpio1->set = (1 << LED_GREEN) | (1 << LED_RED);
-                       break;
-               case toggle:
-                       gpio1->toggle = (1 << LED_GREEN) | (1 << LED_RED);
-                       break;
-               case none:
-               default:
-                       gpio1->clear = (1 << LED_GREEN) | (1 << LED_RED);
-                       break;
-       }
-}
-
-void chenillard(uint32_t ms)
-{
-    status_led(red_only);
-    msleep(ms);
-    status_led(green_only);
-    msleep(ms);
-    status_led(none);
-    msleep(ms);
-    status_led(both);
-    msleep(ms);
-    status_led(none);
-    msleep(ms);
-    status_led(red_only);
-    msleep(ms);
-    status_led(red_only);
-    msleep(ms);
-    status_led(none);
-    msleep(ms);
-    status_led(green_only);
-    msleep(ms);
-    status_led(green_only);
-    msleep(ms);
-    status_led(none);
-    msleep(ms);
-}
diff --git a/drivers/tmp101_temp_sensor.c b/drivers/tmp101_temp_sensor.c
deleted file mode 100644 (file)
index e358c75..0000000
+++ /dev/null
@@ -1,200 +0,0 @@
-/****************************************************************************
- *   drivers/temp.c
- *
- *
- * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
- *
- *
- * 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 <http://www.gnu.org/licenses/>.
- *
- *************************************************************************** */
-
-#include <stdint.h>
-
-#include "core/lpc_regs_12xx.h"
-#include "core/lpc_core_cm0.h"
-#include "core/system.h"
-#include "drivers/i2c.h"
-#include "drivers/tmp101_temp_sensor.h"
-
-
-/***************************************************************************** */
-/*          Support for TMP101 temperature sensors from Texas Instrument       */
-/***************************************************************************** */
-/* This driver is made for the TMP101 version of the chip, though there's few
- * diferences between the TMP100 and TMP101 version.
- * This driver does not handle the SMBus Alert command.
- */
-
-
-/* Config */
-#define TMP101_ADDR  0x94
-
-enum tmp10x_internal_reg_numbers {
-       TMP_REG_TEMPERATURE = 0,
-       TMP_REG_CONFIG,
-       TMP_REG_ALERT_LOW,
-       TMP_REG_ALERT_HIGH,
-};
-
-
-/* Aditional defines, not exported to userspace */
-/* Mode config */
-#define TMP_SHUTDOWN_MODE_ON            (1 << 0)
-#define TMP_THERMOSTAT_COMPARATOR_MODE  (0 << 1)
-#define TMP_THERMOSTAT_INTERRUPT_MODE   (1 << 1)
-/* Alert signal polarity */
-#define TMP_ALERT_POLARITY_LOW          (0 << 2)
-#define TMP_ALERT_POLARITY_HIGH         (1 << 2)
-/* One-shot measurement trigger */
-#define TMP_ONE_SHOT_TRIGGER            (1 << 7)
-
-
-
-/* This static value is used to keep track of the last register accessed to
- * prevent sending the pointer register again if we want to read the same
- * register again. */
-static int last_accessed_register = 0;
-
-/* Check the sensor presence, return 1 if sensor was found.
- * This is a basic check, it could be anything with the same address ...
- */
-int tmp101_probe_sensor(void)
-{
-       static int ret = -1;
-       char cmd_buf[1] = { (TMP101_ADDR | I2C_READ_BIT), };
-
-       /* Did we already probe the sensor ? */
-       if (ret != 1) {
-               ret = i2c_read(cmd_buf, 1, NULL, NULL, 0);
-       }
-       return ret;
-}
-
-/* Convert raw temperature data (expressed as signed value of 16 times the
- * actual temperature in the twelve higher bits of a sixteen bits wide value)
- * into a decimal integer value of ten times the actual temperature.
- * The value returned is thus in tenth of degrees centigrade.
- */
-int tmp101_convert_to_deci_degrees(uint16_t raw)
-{
-       return (((int16_t)raw * 10) >> 8);
-}
-
-/* Temp Read
- * Performs a non-blocking read of the temperature from the sensor.
- * RETURN VALUE
- *   Upon successfull completion, returns 0 and the temperature read is placed in the
- *   provided integer. On error, returns a negative integer equivalent to errors from glibc.
- *   -EBADFD : I2C not initialized
- *   -EBUSY : Device or ressource Busy or Arbitration lost
- *   -EINVAL : Invalid argument (buf)
- *   -ENODEV : No such device
- *   -EREMOTEIO : Device did not acknowledge : Any device present ?
- *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
- */
-#define CMD_BUF_SIZE 3
-int tmp101_sensor_read(uint16_t* raw, int* deci_degrees)
-{
-       int ret = 0;
-       uint16_t temp = 0;
-       char cmd_buf[CMD_BUF_SIZE] = { TMP101_ADDR, TMP_REG_TEMPERATURE, (TMP101_ADDR | I2C_READ_BIT), };
-       char ctrl_buf[CMD_BUF_SIZE] = { I2C_CONT, I2C_DO_REPEATED_START, I2C_CONT, };
-
-       if (tmp101_probe_sensor() != 1) {
-               return -ENODEV;
-       }
-
-       /* Read the requested data */
-       if (last_accessed_register == TMP_REG_TEMPERATURE) {
-               /* No need to switch back to temperature register */
-               ret = i2c_read((cmd_buf + 2), 1, (ctrl_buf + 2), (char*)&temp, 2);
-       } else {
-               /* Send (write) temperature register address to TMP101 internal pointer */
-               ret = i2c_read(cmd_buf, CMD_BUF_SIZE, ctrl_buf, (char*)&temp, 2);
-               last_accessed_register = TMP_REG_TEMPERATURE;
-       }
-
-       if (ret == 2) {
-               if (raw != NULL) {
-                       *raw = byte_swap_16(temp);
-               }
-               if (deci_degrees != NULL) {
-                       *deci_degrees = tmp101_convert_to_deci_degrees(byte_swap_16(temp));
-               }
-               return 0;
-       }
-       return ret;
-}
-
-
-/* Sensor config
- * Performs default configuration of the temperature sensor.
- * The sensor is thus placed in shutdown mode, the thermostat is in interrupt mode,
- * and the polarity is set to active high.
- * The conversion resolution is set to the provided "resolution".
- * RETURN VALUE
- *   Upon successfull completion, returns 0. On error, returns a negative integer
- *   equivalent to errors from glibc.
- *   -EBADFD : I2C not initialized
- *   -EBUSY : Device or ressource Busy or Arbitration lost
- *   -EINVAL : Invalid argument (buf)
- *   -ENODEV : No such device
- *   -EREMOTEIO : Device did not acknowledge : Any device present ?
- *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
- */
-static uint8_t actual_config = 0;
-#define CONF_BUF_SIZE 4
-int tmp101_sensor_config(uint32_t resolution)
-{
-       int ret = 0;
-       char cmd[CONF_BUF_SIZE] = { TMP101_ADDR, TMP_REG_CONFIG, };
-
-       if (tmp101_probe_sensor() != 1) {
-               return -ENODEV;
-       }
-
-       /* Store the new configuration */
-       actual_config = (TMP_SHUTDOWN_MODE_ON | TMP_THERMOSTAT_INTERRUPT_MODE | TMP_ALERT_POLARITY_HIGH);
-       actual_config |= (resolution & (0x03 << 5));
-       cmd[2] = actual_config;
-       ret = i2c_write(cmd, 3, NULL);
-       last_accessed_register = TMP_REG_CONFIG;
-       if (ret == 3) {
-               return 0; /* Config success */
-       }
-       return ret;
-}
-
-/* Start a conversion when the sensor is in shutdown mode. */
-int tmp101_sensor_start_conversion(void)
-{
-       int ret = 0;
-       char cmd[CONF_BUF_SIZE] = { TMP101_ADDR, TMP_REG_CONFIG, };
-
-       if (tmp101_probe_sensor() != 1) {
-               return -ENODEV;
-       }
-
-       cmd[2] = actual_config;
-       cmd[2] |= TMP_ONE_SHOT_TRIGGER;
-       ret = i2c_write(cmd, 3, NULL);
-       last_accessed_register = TMP_REG_CONFIG;
-       if (ret == 3) {
-               return 0; /* Conversion start success */
-       }
-       return ret;
-}
-
-
diff --git a/extdrv/cc1101.c b/extdrv/cc1101.c
new file mode 100644 (file)
index 0000000..b788648
--- /dev/null
@@ -0,0 +1,465 @@
+/****************************************************************************
+ *  extdrv/cc1101.c
+ *
+ * Copyright 2014 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#include <stdint.h>
+#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 "extdrv/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);
+       }
+       /* Release Chip select */
+       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));
+       if (status != NULL) {
+               *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 */
+
+
+/* Change the CC1101 address
+ * Only packets addressed to the specified address (or broadcasted) will be
+*    received.
+ * Adresses 0x00 and 0xFF are broadcast
+ * This function places the CC1101 chip in idle state.
+ */
+void cc1101_set_address(uint8_t address)
+{
+       cc1101_send_cmd(CC1101_CMD(state_idle));
+       cc1101_write_reg(CC1101_REGS(device_addr), address);
+}
+
+/* Change a configuration byte.
+ * This function places the CC1101 chip in idle state.
+ */
+void cc1101_set_config(uint8_t byte_addr, uint8_t value)
+{
+       cc1101_send_cmd(CC1101_CMD(state_idle));
+       cc1101_write_reg(byte_addr, value);
+}
+
+/* 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]), 0x07, /* GDO_0 - Assert on CRC OK | 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 = NULL;
+
+       if ((cs_pin == NULL) || (miso_pin == NULL)) {
+               return;
+       }
+       gpio = LPC_GPIO_REGS(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/extdrv/eeprom.c b/extdrv/eeprom.c
new file mode 100644 (file)
index 0000000..2f35fec
--- /dev/null
@@ -0,0 +1,263 @@
+/****************************************************************************
+ *   extdrv/eeprom.c
+ *
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#include <stdint.h>
+
+#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/i2c.h"
+#include "extdrv/eeprom.h"
+
+
+/***************************************************************************** */
+/*       EEPROM Chip select for the GPIO Demo module                           */
+/*******************************************************************************/
+/* Set the SPI SSEL pin low. */
+/* These functions are specific to the mod_gpio_demo and domotab modules.
+ * It is used to release the gate that blocks the SCL signal to the EEPROM,
+ *   allowing multiple eeproms with the same address to be accessed one at a time
+ *   on the same I2C Bus, which gives a way to both identify modules presence and
+ *   module function, name, and pther capabilities.
+ * When the SPI is used as slave, the master has the control of the SPI SSEL signal
+ *   and the EEPROM should not be accessed by the module.
+ * Other I2C EEPROMs should not need these functions.
+ */
+static struct pio i2c_eeprom_cs = LPC_GPIO_0_15;
+int mod_gpio_demo_eeprom_cs_pull_low(void)
+{
+    struct lpc_gpio* gpio_port_regs = LPC_GPIO_REGS(i2c_eeprom_cs.port);
+    config_pio(&i2c_eeprom_cs, (LPC_IO_MODE_PULL_UP | LPC_IO_DIGITAL));
+    /* Configure SPI_CS as output and set it low. */
+    gpio_port_regs->data_dir |= (1 << i2c_eeprom_cs.pin);
+    gpio_port_regs->clear = (1 << i2c_eeprom_cs.pin);
+       return 0;
+}
+void mod_gpio_demo_eeprom_cs_release(void)
+{
+       struct lpc_gpio* gpio_port_regs = LPC_GPIO_REGS(i2c_eeprom_cs.port);
+    gpio_port_regs->set = (1 << i2c_eeprom_cs.pin);
+}
+
+
+/***************************************************************************** */
+/*          Read and Write for module eeprom                                   */
+/***************************************************************************** */
+/* Config */
+/* Small eeprom : up to 2k bytes. These use a segment address on the lower three bits
+ *   of the address byte, and thus reply on 8 consecutive addresses */
+#define EEPROM_ID_SMALL_ADDR  0xA0
+#define EEPROM_ID_SMALL_I2C_SIZE  1024
+#define EEPROM_ID_SMALL_PAGE_SIZE 16
+/* Big eeprom : from 4k bytes and above : These use two address bytes, and the three
+ *   physical address pins are used to set the chip address. On DTPlug modules they should
+ *   have address 0xA8. */
+#define EEPROM_ID_BIG_ADDR  0xA8
+#define EEPROM_ID_BIG_I2C_SIZE  16*1024
+#define EEPROM_ID_BIG_PAGE_SIZE 64
+
+
+
+/* Detect the eeprom size */
+int eeprom_detect(void)
+{
+       int ret = 0;
+       char cmd_buf[1] = { EEPROM_ID_SMALL_ADDR, };
+
+       /* Look for small eeproms first, only these would answer on EEPROM_ID_SMALL_ADDR */
+       ret = i2c_read(cmd_buf, 1, NULL, NULL, 0);
+       if (ret == 0) {
+               return EEPROM_TYPE_SMALL;
+       }
+       /* No small eeprom ... look for big ones */
+       cmd_buf[0] = EEPROM_ID_BIG_ADDR;
+       ret = i2c_read(cmd_buf, 1, NULL, NULL, 0);
+       if (ret == 0) {
+               return EEPROM_TYPE_BIG;
+       }
+
+       if (ret > 0) {
+               return -EIO;
+       } else if (ret == -EREMOTEIO) {
+               return EEPROM_TYPE_NONE; /* No module */
+       }
+       return ret; /* Error or module size */
+}
+
+int get_eeprom_type(void)
+{
+       static int eeprom_type = -1;
+
+       if (eeprom_type >= 0) {
+               return eeprom_type; /* No need to check again */
+       }
+
+       eeprom_type = eeprom_detect();
+       if (eeprom_type <= 0) {
+               return -1;
+       }
+       return eeprom_type;
+}
+
+
+/* EEPROM Read
+ * Performs a non-blocking read on the eeprom.
+ *   address : data offset in eeprom.
+ * RETURN VALUE
+ *   Upon successfull completion, returns the number of bytes read. On error, returns a negative
+ *   integer equivalent to errors from glibc.
+ *   -EFAULT : address above eeprom size
+ *   -EBADFD : Device not initialized
+ *   -EBUSY : Device or ressource Busy or Arbitration lost
+ *   -EAGAIN : Device already in use
+ *   -EINVAL : Invalid argument (buf)
+ *   -EREMOTEIO : Device did not acknowledge
+ *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
+ */
+#define CMD_BUF_SIZE 4
+int eeprom_read(uint32_t offset, void *buf, size_t count)
+{
+       int ret = 0;
+       char cmd_buf[CMD_BUF_SIZE] = { EEPROM_ID_BIG_ADDR, 0, 0, (EEPROM_ID_BIG_ADDR | 0x01), };
+       char ctrl_buf[CMD_BUF_SIZE] = { I2C_CONT, I2C_CONT, I2C_DO_REPEATED_START, I2C_CONT, };
+       int eeprom_type = 0;
+
+       if (mod_gpio_demo_eeprom_cs_pull_low() != 0) {
+               return -EBUSY;
+       }
+       eeprom_type = get_eeprom_type();
+
+       /* Read the requested data */
+       switch (eeprom_type) {
+               case EEPROM_TYPE_SMALL:
+                       cmd_buf[0] = EEPROM_ID_SMALL_ADDR | ((offset & 0x700) >> 7);
+                       cmd_buf[1] = offset & 0xFF;
+                       cmd_buf[2] = EEPROM_ID_SMALL_ADDR | 0x01;
+                       ret = i2c_read(cmd_buf, CMD_BUF_SIZE - 1, ctrl_buf + 1, buf, count);
+                       break;
+               case EEPROM_TYPE_BIG:
+                       cmd_buf[1] = ((offset & 0xFF00) >> 8);
+                       cmd_buf[2] = offset & 0xFF;
+                       ret = i2c_read(cmd_buf, CMD_BUF_SIZE, ctrl_buf, buf, count);
+                       break;
+               default:
+                       ret = -1;
+                       break;
+       }
+       mod_gpio_demo_eeprom_cs_release();
+
+       return ret;
+}
+
+
+/* EEPROM Write
+ * Performs a non-blocking write on the eeprom.
+ *   address : data offset in eeprom.
+ * RETURN VALUE
+ *   Upon successfull completion, returns the number of bytes written. On error, returns a negative
+ *   integer equivalent to errors from glibc.
+ *   -EFAULT : address above eeprom size
+ *   -EBADFD : Device not initialized
+ *   -EBUSY : Device or ressource Busy or Arbitration lost
+ *   -EAGAIN : Device already in use
+ *   -EINVAL : Invalid argument (buf)
+ *   -EREMOTEIO : Device did not acknowledge
+ *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
+ */
+#define CMD_SIZE_SMALL 2
+#define CMD_SIZE_BIG 3
+#define MAX_CMD_SIZE CMD_SIZE_BIG
+#define EEPROM_ID_MAX_PAGE_SIZE EEPROM_ID_BIG_PAGE_SIZE
+int eeprom_write(uint32_t offset, const void *buf, size_t count)
+{
+       int ret = 0;
+       uint8_t cmd_size = CMD_SIZE_BIG, page_size = EEPROM_ID_BIG_PAGE_SIZE;
+       int write_count = 0, size = 0;
+       char cmd[MAX_CMD_SIZE] = { EEPROM_ID_BIG_ADDR, 0, 0 };
+       char full_buff[(EEPROM_ID_MAX_PAGE_SIZE + MAX_CMD_SIZE)];
+       int eeprom_type = 0;
+
+       if (mod_gpio_demo_eeprom_cs_pull_low() != 0) {
+               return -EBUSY;
+       }
+       eeprom_type = get_eeprom_type();
+
+       switch (eeprom_type) {
+               case EEPROM_TYPE_SMALL:
+                       cmd_size = CMD_SIZE_SMALL;
+                       page_size = EEPROM_ID_SMALL_PAGE_SIZE;
+                       break;
+               case EEPROM_TYPE_BIG:
+                       /* already configured */
+                       /* cmd_size = CMD_SIZE_BIG; */
+                       /* page_size = EEPROM_ID_BIG_PAGE_SIZE; */
+                       break;
+               default:
+                       ret = -1;
+                       write_count = count + 1; /* skip the while loop, but return error */
+                       break;
+       }
+       while (write_count < count) {
+               switch (eeprom_type) {
+                       case EEPROM_TYPE_SMALL:
+                               cmd[0] = EEPROM_ID_SMALL_ADDR | ((offset & 0x700) >> 7);
+                               cmd[1] = offset & 0xFF;
+                               break;
+                       case EEPROM_TYPE_BIG:
+                               cmd[1] = ((offset & 0xFF00) >> 8);
+                               cmd[2] = offset & 0xFF;
+                               break;
+               }
+               /* make partial first write to allign to page boundaries */
+               if (offset & (page_size - 1)) {
+                       size = (page_size - (offset & (page_size - 1)));
+               } else {
+                       size = page_size;
+               }
+               if (size > (count - write_count))
+                       size = (count - write_count);
+               offset += size;
+               memcpy(full_buff, cmd, cmd_size);
+               memcpy(full_buff + cmd_size, buf + write_count, size);
+               ret = i2c_write(full_buff, (cmd_size + size), NULL);
+
+               if (ret != (cmd_size + size)) {
+                       break;
+               }
+               /* Wait for page write completion : The device does not acknoledge anything during
+                * page write, perform page writes with no data, until it returns 1 */
+               do {
+                       ret = i2c_write(full_buff, 1, NULL);
+               } while (ret != 1);
+
+               write_count += size;
+       }
+       mod_gpio_demo_eeprom_cs_release();
+
+       if (write_count != count)
+               return ret;
+       return write_count;
+}
+
+
diff --git a/extdrv/status_led.c b/extdrv/status_led.c
new file mode 100644 (file)
index 0000000..8ae531a
--- /dev/null
@@ -0,0 +1,136 @@
+/****************************************************************************
+ *  extdrv/status_led.c
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ *
+*************************************************************************** */
+
+/***************************************************************************** */
+/*                Status Led                                                   */
+/***************************************************************************** */
+
+
+#include <stdint.h>
+#include "core/lpc_regs_12xx.h"
+#include "core/system.h"
+#include "core/pio.h"
+#include "extdrv/status_led.h"
+
+
+/***************************************************************************** */
+/* Status LED is the bicolors red/green led on the GPIO Demo module */
+
+/* This code configures the status led and enables it's use as a debug helper
+ * or visual watchdog.
+ * Calls to chenillard() with a value of about 25ms or more will trigger a
+ * defined sequence to be displayed by the status led.
+ * This sequence implies a big delay in your code (eleven times the value used
+ * as argument in ms.
+ *
+ * If you want to use this led in a more application friendly way (with no sleep)
+ * you must use a timer to call a "stepping" routine (either systick timer or any
+ * of the other four timers).
+ */
+
+/* The status LED is on GPIO Port 1, pin 4 (PIO1_4) and Port 1, pin 5 (PIO1_5) */
+#define LED_RED    5
+#define LED_GREEN  4
+
+void status_led_config(void)
+{
+       struct lpc_gpio* gpio1 = LPC_GPIO_REGS(1);
+       uint32_t mode = (LPC_IO_MODE_PULL_UP | LPC_IO_DIGITAL | LPC_IO_DRIVE_HIGHCURENT);
+       struct pio red_led = LPC_GPIO_1_5;
+       struct pio green_led = LPC_GPIO_1_4;
+       /* Status Led GPIO */
+       config_pio(&green_led, mode);
+       config_pio(&red_led, mode);
+       /* Configure both as output */
+       gpio1->data_dir |= (1 << LED_GREEN) | (1 << LED_RED);
+       /* Turn both LEDs on */
+       //gpio1->set = (1 << LED_GREEN) | (1 << LED_RED);
+       gpio1->set = (1 << LED_GREEN);
+}
+
+void status_led(uint32_t val)
+{
+       struct lpc_gpio* gpio1 = LPC_GPIO_REGS(1);
+
+       switch (val) {
+               case red_only:
+                       gpio1->set = (1 << LED_RED);
+                       gpio1->clear = (1 << LED_GREEN);
+                       break;
+               case red_on:
+                       gpio1->set = (1 << LED_RED);
+                       break;
+               case red_off:
+                       gpio1->clear = (1 << LED_RED);
+                       break;
+               case red_toggle:
+                       gpio1->toggle = (1 << LED_RED);
+                       break;
+               case green_only:
+                       gpio1->set = (1 << LED_GREEN);
+                       gpio1->clear = (1 << LED_RED);
+                       break;
+               case green_on:
+                       gpio1->set = (1 << LED_GREEN);
+                       break;
+               case green_off:
+                       gpio1->clear = (1 << LED_GREEN);
+                       break;
+               case green_toggle:
+                       gpio1->toggle = (1 << LED_GREEN);
+                       break;
+               case both:
+                       gpio1->set = (1 << LED_GREEN) | (1 << LED_RED);
+                       break;
+               case toggle:
+                       gpio1->toggle = (1 << LED_GREEN) | (1 << LED_RED);
+                       break;
+               case none:
+               default:
+                       gpio1->clear = (1 << LED_GREEN) | (1 << LED_RED);
+                       break;
+       }
+}
+
+void chenillard(uint32_t ms)
+{
+    status_led(red_only);
+    msleep(ms);
+    status_led(green_only);
+    msleep(ms);
+    status_led(none);
+    msleep(ms);
+    status_led(both);
+    msleep(ms);
+    status_led(none);
+    msleep(ms);
+    status_led(red_only);
+    msleep(ms);
+    status_led(red_only);
+    msleep(ms);
+    status_led(none);
+    msleep(ms);
+    status_led(green_only);
+    msleep(ms);
+    status_led(green_only);
+    msleep(ms);
+    status_led(none);
+    msleep(ms);
+}
diff --git a/extdrv/tmp101_temp_sensor.c b/extdrv/tmp101_temp_sensor.c
new file mode 100644 (file)
index 0000000..3571c18
--- /dev/null
@@ -0,0 +1,200 @@
+/****************************************************************************
+ *   extdrv/temp.c
+ *
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#include <stdint.h>
+
+#include "core/lpc_regs_12xx.h"
+#include "core/lpc_core_cm0.h"
+#include "core/system.h"
+#include "drivers/i2c.h"
+#include "extdrv/tmp101_temp_sensor.h"
+
+
+/***************************************************************************** */
+/*          Support for TMP101 temperature sensors from Texas Instrument       */
+/***************************************************************************** */
+/* This driver is made for the TMP101 version of the chip, though there's few
+ * diferences between the TMP100 and TMP101 version.
+ * This driver does not handle the SMBus Alert command.
+ */
+
+
+/* Config */
+#define TMP101_ADDR  0x94
+
+enum tmp10x_internal_reg_numbers {
+       TMP_REG_TEMPERATURE = 0,
+       TMP_REG_CONFIG,
+       TMP_REG_ALERT_LOW,
+       TMP_REG_ALERT_HIGH,
+};
+
+
+/* Aditional defines, not exported to userspace */
+/* Mode config */
+#define TMP_SHUTDOWN_MODE_ON            (1 << 0)
+#define TMP_THERMOSTAT_COMPARATOR_MODE  (0 << 1)
+#define TMP_THERMOSTAT_INTERRUPT_MODE   (1 << 1)
+/* Alert signal polarity */
+#define TMP_ALERT_POLARITY_LOW          (0 << 2)
+#define TMP_ALERT_POLARITY_HIGH         (1 << 2)
+/* One-shot measurement trigger */
+#define TMP_ONE_SHOT_TRIGGER            (1 << 7)
+
+
+
+/* This static value is used to keep track of the last register accessed to
+ * prevent sending the pointer register again if we want to read the same
+ * register again. */
+static int last_accessed_register = 0;
+
+/* Check the sensor presence, return 1 if sensor was found.
+ * This is a basic check, it could be anything with the same address ...
+ */
+int tmp101_probe_sensor(void)
+{
+       static int ret = -1;
+       char cmd_buf[1] = { (TMP101_ADDR | I2C_READ_BIT), };
+
+       /* Did we already probe the sensor ? */
+       if (ret != 1) {
+               ret = i2c_read(cmd_buf, 1, NULL, NULL, 0);
+       }
+       return ret;
+}
+
+/* Convert raw temperature data (expressed as signed value of 16 times the
+ * actual temperature in the twelve higher bits of a sixteen bits wide value)
+ * into a decimal integer value of ten times the actual temperature.
+ * The value returned is thus in tenth of degrees centigrade.
+ */
+int tmp101_convert_to_deci_degrees(uint16_t raw)
+{
+       return (((int16_t)raw * 10) >> 8);
+}
+
+/* Temp Read
+ * Performs a non-blocking read of the temperature from the sensor.
+ * RETURN VALUE
+ *   Upon successfull completion, returns 0 and the temperature read is placed in the
+ *   provided integer. On error, returns a negative integer equivalent to errors from glibc.
+ *   -EBADFD : I2C not initialized
+ *   -EBUSY : Device or ressource Busy or Arbitration lost
+ *   -EINVAL : Invalid argument (buf)
+ *   -ENODEV : No such device
+ *   -EREMOTEIO : Device did not acknowledge : Any device present ?
+ *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
+ */
+#define CMD_BUF_SIZE 3
+int tmp101_sensor_read(uint16_t* raw, int* deci_degrees)
+{
+       int ret = 0;
+       uint16_t temp = 0;
+       char cmd_buf[CMD_BUF_SIZE] = { TMP101_ADDR, TMP_REG_TEMPERATURE, (TMP101_ADDR | I2C_READ_BIT), };
+       char ctrl_buf[CMD_BUF_SIZE] = { I2C_CONT, I2C_DO_REPEATED_START, I2C_CONT, };
+
+       if (tmp101_probe_sensor() != 1) {
+               return -ENODEV;
+       }
+
+       /* Read the requested data */
+       if (last_accessed_register == TMP_REG_TEMPERATURE) {
+               /* No need to switch back to temperature register */
+               ret = i2c_read((cmd_buf + 2), 1, (ctrl_buf + 2), (char*)&temp, 2);
+       } else {
+               /* Send (write) temperature register address to TMP101 internal pointer */
+               ret = i2c_read(cmd_buf, CMD_BUF_SIZE, ctrl_buf, (char*)&temp, 2);
+               last_accessed_register = TMP_REG_TEMPERATURE;
+       }
+
+       if (ret == 2) {
+               if (raw != NULL) {
+                       *raw = byte_swap_16(temp);
+               }
+               if (deci_degrees != NULL) {
+                       *deci_degrees = tmp101_convert_to_deci_degrees(byte_swap_16(temp));
+               }
+               return 0;
+       }
+       return ret;
+}
+
+
+/* Sensor config
+ * Performs default configuration of the temperature sensor.
+ * The sensor is thus placed in shutdown mode, the thermostat is in interrupt mode,
+ * and the polarity is set to active high.
+ * The conversion resolution is set to the provided "resolution".
+ * RETURN VALUE
+ *   Upon successfull completion, returns 0. On error, returns a negative integer
+ *   equivalent to errors from glibc.
+ *   -EBADFD : I2C not initialized
+ *   -EBUSY : Device or ressource Busy or Arbitration lost
+ *   -EINVAL : Invalid argument (buf)
+ *   -ENODEV : No such device
+ *   -EREMOTEIO : Device did not acknowledge : Any device present ?
+ *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
+ */
+static uint8_t actual_config = 0;
+#define CONF_BUF_SIZE 4
+int tmp101_sensor_config(uint32_t resolution)
+{
+       int ret = 0;
+       char cmd[CONF_BUF_SIZE] = { TMP101_ADDR, TMP_REG_CONFIG, };
+
+       if (tmp101_probe_sensor() != 1) {
+               return -ENODEV;
+       }
+
+       /* Store the new configuration */
+       actual_config = (TMP_SHUTDOWN_MODE_ON | TMP_THERMOSTAT_INTERRUPT_MODE | TMP_ALERT_POLARITY_HIGH);
+       actual_config |= (resolution & (0x03 << 5));
+       cmd[2] = actual_config;
+       ret = i2c_write(cmd, 3, NULL);
+       last_accessed_register = TMP_REG_CONFIG;
+       if (ret == 3) {
+               return 0; /* Config success */
+       }
+       return ret;
+}
+
+/* Start a conversion when the sensor is in shutdown mode. */
+int tmp101_sensor_start_conversion(void)
+{
+       int ret = 0;
+       char cmd[CONF_BUF_SIZE] = { TMP101_ADDR, TMP_REG_CONFIG, };
+
+       if (tmp101_probe_sensor() != 1) {
+               return -ENODEV;
+       }
+
+       cmd[2] = actual_config;
+       cmd[2] |= TMP_ONE_SHOT_TRIGGER;
+       ret = i2c_write(cmd, 3, NULL);
+       last_accessed_register = TMP_REG_CONFIG;
+       if (ret == 3) {
+               return 0; /* Conversion start success */
+       }
+       return ret;
+}
+
+
diff --git a/include/drivers/cc1101.h b/include/drivers/cc1101.h
deleted file mode 100644 (file)
index c9c4c11..0000000
+++ /dev/null
@@ -1,269 +0,0 @@
-/**
- * @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
- *    underflow 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 */
-
-/* Change the CC1101 address
- * Only packets addressed to the specified address (or broadcasted) will be
-*    received.
- * Adresses 0x00 and 0xFF are broadcast
- * This function places the CC1101 chip in idle state.
- */
-void cc1101_set_address(uint8_t address);
-
-/* Change a configuration byte.
- * This function places the CC1101 chip in idle state.
- */
-void cc1101_set_config(uint8_t byte_addr, uint8_t value);
-
-/* 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 */
index 1782298..de21457 100644 (file)
@@ -74,70 +74,6 @@ enum i2c_state_machine_states {
 };
 
 
-/***************************************************************************** */
-/*       Module identification support for DTPlug and DomoTab                  */
-/***************************************************************************** */
-
-/* Module capabilities */
-#define UEXT_MOD_HAS_NONE  0
-#define UEXT_MOD_HAS_UART (1 << 0)
-#define UEXT_MOD_HAS_I2C  (1 << 1)
-#define UEXT_MOD_HAS_SPI  (1 << 2)
-
-struct module_desc {
-       uint16_t serial_number;
-       uint8_t version;
-       uint8_t header_size;
-       uint8_t capabilities; /* Bit mask of UEXT_MOD_HAS_* */
-       uint8_t name_offset;
-       uint8_t name_size;
-       uint8_t image_offset;
-       uint16_t image_size;
-} __attribute__ ((packed));
-
-enum i2c_eeprom_type {
-       EEPROM_TYPE_NONE = 0,
-       EEPROM_TYPE_SMALL,
-       EEPROM_TYPE_BIG,
-};
-
-
-
-/***************************************************************************** */
-/*          Read and Write for system eeprom                                   */
-/***************************************************************************** */
-/* EEPROM Read
- * Performs a non-blocking read on the eeprom.
- *   address : data offset in eeprom.
- * RETURN VALUE
- *   Upon successfull completion, returns the number of bytes read. On error, returns a negative
- *   integer equivalent to errors from glibc.
- *   -EFAULT : address above eeprom size
- *   -EBADFD : Device not initialized
- *   -EBUSY : Device or ressource Busy or Arbitration lost
- *   -EAGAIN : Device already in use
- *   -EINVAL : Invalid argument (buf)
- *   -EREMOTEIO : Device did not acknowledge
- *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
- */
-int eeprom_read(uint32_t offset, void *buf, size_t count);
-
-/* EEPROM Write
- * Performs a non-blocking write on the eeprom.
- *   address : data offset in eeprom.
- * RETURN VALUE
- *   Upon successfull completion, returns the number of bytes written. On error, returns a negative
- *   integer equivalent to errors from glibc.
- *   -EFAULT : address above eeprom size
- *   -EBADFD : Device not initialized
- *   -EBUSY : Device or ressource Busy or Arbitration lost
- *   -EAGAIN : Device already in use
- *   -EINVAL : Invalid argument (buf)
- *   -EREMOTEIO : Device did not acknowledge
- *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
- */
-int eeprom_write(uint32_t offset, const void *buf, size_t count);
-
 
 
 /***************************************************************************** */
diff --git a/include/drivers/status_led.h b/include/drivers/status_led.h
deleted file mode 100644 (file)
index 50ecc96..0000000
+++ /dev/null
@@ -1,52 +0,0 @@
-/****************************************************************************
- *  drivers/status_led.h
- *
- * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
- *
- * 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 <http://www.gnu.org/licenses/>.
- *
- *************************************************************************** */
-
-#ifndef DRIVERS_STATUS_LED_H
-#define DRIVERS_STATUS_LED_H
-
-
-#include <stdint.h>
-
-
-/***************************************************************************** */
-/* Status LED */
-/* The status LED is on GPIO Port 1, pin 4 (PIO1_4) and Port 1, pin 5 (PIO1_5) */
-void status_led_config(void);
-
-void status_led(uint32_t val);
-
-void chenillard(uint32_t ms);
-
-enum led_status {
-       none = 0,
-       red_only,
-       red_on,
-       red_off,
-       red_toggle,
-       green_only,
-       green_on,
-       green_off,
-       green_toggle,
-       both,
-       toggle,
-};
-
-
-#endif /* DRIVERS_STATUS_LED_H */
diff --git a/include/drivers/tmp101_temp_sensor.h b/include/drivers/tmp101_temp_sensor.h
deleted file mode 100644 (file)
index a3f4369..0000000
+++ /dev/null
@@ -1,103 +0,0 @@
-/****************************************************************************
- *   drivers/temp.h
- *
- *
- * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
- *
- *
- * 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 <http://www.gnu.org/licenses/>.
- *
- *************************************************************************** */
-
-#ifndef DRIVERS_TEMP_H
-#define DRIVERS_TEMP_H
-
-#include <stdint.h>
-
-
-/***************************************************************************** */
-/*          Support for TMP101 temperature sensors from Texas Instrument       */
-/***************************************************************************** */
-/* This driver is made for the TMP101 version of the chip, though there's few
- * diferences between the TMP100 and TMP101 version.
- * This driver does not handle the SMBus Alert command.
- */
-
-
-/* Faulty mesures required to trigger alert */
-#define TMP_FAULT_ONE       ((0x00 & 0x03) << 3)
-#define TMP_FAULT_TWO       ((0x01 & 0x03) << 3)
-#define TMP_FAULT_FOUR      ((0x02 & 0x03) << 3)
-#define TMP_FAULT_SIX       ((0x03 & 0x03) << 3)
-
-/* Temp mesurement resolution bits */            /* conversion time */
-#define TMP_RES_NINE_BITS   ((0x00 & 0x03) << 5)   /*  40ms */
-#define TMP_RES_TEN_BITS    ((0x01 & 0x03) << 5)   /*  80ms */
-#define TMP_RES_ELEVEN_BITS ((0x02 & 0x03) << 5)   /* 160ms */
-#define TMP_RES_TWELVE_BITS ((0x03 & 0x03) << 5)   /* 320ms */
-
-
-/* Check the sensor presence, return 1 if found
- * This is a basic check, it could be anything with the same address ...
- */
-int tmp101_probe_sensor(void);
-
-
-/* Convert raw temperature data (expressed as signed value of 16 times the
- * actual temperature in the twelve higher bits of a sixteen bits wide value)
- * into a decimal interger value of ten times the actual temperature.
- * The value returned is thus in tenth of degrees centigrade.
- */
-int tmp101_convert_to_deci_degrees(uint16_t raw);
-
-
-/* Temp Read
- * Performs a non-blocking read of the temperature from the sensor.
- * RETURN VALUE
- *   Upon successfull completion, returns 0 and the temperature read is placed in the
- *   provided integer(s). On error, returns a negative integer equivalent to errors from
- *   glibc.
- *   -EBADFD : I2C not initialized
- *   -EBUSY : Device or ressource Busy or Arbitration lost
- *   -EINVAL : Invalid argument (buf)
- *   -ENODEV : No such device
- *   -EREMOTEIO : Device did not acknowledge : Any device present ?
- *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
- */
-int tmp101_sensor_read(uint16_t* raw, int* deci_degrees);
-
-
-/* Sensor config
- * Performs default configuration of the temperature sensor.
- * The sensor is thus placed in shutdown mode, the thermostat is in interrupt mode,
- * and the polarity is set to active high.
- * The conversion resolution is set to the provided "resolution".
- * RETURN VALUE
- *   Upon successfull completion, returns 0. On error, returns a negative integer
- *   equivalent to errors from glibc.
- *   -EBADFD : I2C not initialized
- *   -EBUSY : Device or ressource Busy or Arbitration lost
- *   -EINVAL : Invalid argument (buf)
- *   -ENODEV : No such device
- *   -EREMOTEIO : Device did not acknowledge : Any device present ?
- *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
- */
-int tmp101_sensor_config(uint32_t resolution);
-
-/* Start a conversion when the sensor is in shutdown mode. */
-int tmp101_sensor_start_conversion(void);
-
-
-#endif /* DRIVERS_TEMP_H */
-
diff --git a/include/extdrv/cc1101.h b/include/extdrv/cc1101.h
new file mode 100644 (file)
index 0000000..2f7b4e7
--- /dev/null
@@ -0,0 +1,269 @@
+/**
+ * @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 EXTDRV_CC1101_H
+#define EXTDRV_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
+ *    underflow 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 */
+
+/* Change the CC1101 address
+ * Only packets addressed to the specified address (or broadcasted) will be
+*    received.
+ * Adresses 0x00 and 0xFF are broadcast
+ * This function places the CC1101 chip in idle state.
+ */
+void cc1101_set_address(uint8_t address);
+
+/* Change a configuration byte.
+ * This function places the CC1101 chip in idle state.
+ */
+void cc1101_set_config(uint8_t byte_addr, uint8_t value);
+
+/* 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 /* EXTDRV_CC1101_H */
diff --git a/include/extdrv/eeprom.h b/include/extdrv/eeprom.h
new file mode 100644 (file)
index 0000000..2034b7c
--- /dev/null
@@ -0,0 +1,96 @@
+/****************************************************************************
+ *   extdrv/eeprom.h
+ *
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#ifndef EXTDRV_EEPROM_H
+#define EXTDRV_EEPROM_H
+
+#include <stdint.h>
+
+
+/***************************************************************************** */
+/*       Module identification support for DTPlug and DomoTab                  */
+/***************************************************************************** */
+
+/* Module capabilities */
+#define UEXT_MOD_HAS_NONE  0
+#define UEXT_MOD_HAS_UART (1 << 0)
+#define UEXT_MOD_HAS_I2C  (1 << 1)
+#define UEXT_MOD_HAS_SPI  (1 << 2)
+
+struct module_desc {
+       uint16_t serial_number;
+       uint8_t version;
+       uint8_t header_size;
+       uint8_t capabilities; /* Bit mask of UEXT_MOD_HAS_* */
+       uint8_t name_offset;
+       uint8_t name_size;
+       uint8_t image_offset;
+       uint16_t image_size;
+} __attribute__ ((packed));
+
+enum i2c_eeprom_type {
+       EEPROM_TYPE_NONE = 0,
+       EEPROM_TYPE_SMALL,
+       EEPROM_TYPE_BIG,
+};
+
+
+
+/***************************************************************************** */
+/*          Read and Write for system eeprom                                   */
+/***************************************************************************** */
+/* EEPROM Read
+ * Performs a non-blocking read on the eeprom.
+ *   address : data offset in eeprom.
+ * RETURN VALUE
+ *   Upon successfull completion, returns the number of bytes read. On error, returns a negative
+ *   integer equivalent to errors from glibc.
+ *   -EFAULT : address above eeprom size
+ *   -EBADFD : Device not initialized
+ *   -EBUSY : Device or ressource Busy or Arbitration lost
+ *   -EAGAIN : Device already in use
+ *   -EINVAL : Invalid argument (buf)
+ *   -EREMOTEIO : Device did not acknowledge
+ *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
+ */
+int eeprom_read(uint32_t offset, void *buf, size_t count);
+
+/* EEPROM Write
+ * Performs a non-blocking write on the eeprom.
+ *   address : data offset in eeprom.
+ * RETURN VALUE
+ *   Upon successfull completion, returns the number of bytes written. On error, returns a negative
+ *   integer equivalent to errors from glibc.
+ *   -EFAULT : address above eeprom size
+ *   -EBADFD : Device not initialized
+ *   -EBUSY : Device or ressource Busy or Arbitration lost
+ *   -EAGAIN : Device already in use
+ *   -EINVAL : Invalid argument (buf)
+ *   -EREMOTEIO : Device did not acknowledge
+ *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
+ */
+int eeprom_write(uint32_t offset, const void *buf, size_t count);
+
+
+
+
+#endif /* EXTDRV_EEPROM_H */
diff --git a/include/extdrv/status_led.h b/include/extdrv/status_led.h
new file mode 100644 (file)
index 0000000..02f2c00
--- /dev/null
@@ -0,0 +1,52 @@
+/****************************************************************************
+ *  extdrv/status_led.h
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#ifndef EXTDRV_STATUS_LED_H
+#define EXTDRV_STATUS_LED_H
+
+
+#include <stdint.h>
+
+
+/***************************************************************************** */
+/* Status LED */
+/* The status LED is on GPIO Port 1, pin 4 (PIO1_4) and Port 1, pin 5 (PIO1_5) */
+void status_led_config(void);
+
+void status_led(uint32_t val);
+
+void chenillard(uint32_t ms);
+
+enum led_status {
+       none = 0,
+       red_only,
+       red_on,
+       red_off,
+       red_toggle,
+       green_only,
+       green_on,
+       green_off,
+       green_toggle,
+       both,
+       toggle,
+};
+
+
+#endif /* EXTDRV_STATUS_LED_H */
diff --git a/include/extdrv/tmp101_temp_sensor.h b/include/extdrv/tmp101_temp_sensor.h
new file mode 100644 (file)
index 0000000..e84f4e3
--- /dev/null
@@ -0,0 +1,103 @@
+/****************************************************************************
+ *   extdrv/temp.h
+ *
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ *
+ * 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 <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#ifndef EXTDRV_TEMP_H
+#define EXTDRV_TEMP_H
+
+#include <stdint.h>
+
+
+/***************************************************************************** */
+/*          Support for TMP101 temperature sensors from Texas Instrument       */
+/***************************************************************************** */
+/* This driver is made for the TMP101 version of the chip, though there's few
+ * diferences between the TMP100 and TMP101 version.
+ * This driver does not handle the SMBus Alert command.
+ */
+
+
+/* Faulty mesures required to trigger alert */
+#define TMP_FAULT_ONE       ((0x00 & 0x03) << 3)
+#define TMP_FAULT_TWO       ((0x01 & 0x03) << 3)
+#define TMP_FAULT_FOUR      ((0x02 & 0x03) << 3)
+#define TMP_FAULT_SIX       ((0x03 & 0x03) << 3)
+
+/* Temp mesurement resolution bits */            /* conversion time */
+#define TMP_RES_NINE_BITS   ((0x00 & 0x03) << 5)   /*  40ms */
+#define TMP_RES_TEN_BITS    ((0x01 & 0x03) << 5)   /*  80ms */
+#define TMP_RES_ELEVEN_BITS ((0x02 & 0x03) << 5)   /* 160ms */
+#define TMP_RES_TWELVE_BITS ((0x03 & 0x03) << 5)   /* 320ms */
+
+
+/* Check the sensor presence, return 1 if found
+ * This is a basic check, it could be anything with the same address ...
+ */
+int tmp101_probe_sensor(void);
+
+
+/* Convert raw temperature data (expressed as signed value of 16 times the
+ * actual temperature in the twelve higher bits of a sixteen bits wide value)
+ * into a decimal interger value of ten times the actual temperature.
+ * The value returned is thus in tenth of degrees centigrade.
+ */
+int tmp101_convert_to_deci_degrees(uint16_t raw);
+
+
+/* Temp Read
+ * Performs a non-blocking read of the temperature from the sensor.
+ * RETURN VALUE
+ *   Upon successfull completion, returns 0 and the temperature read is placed in the
+ *   provided integer(s). On error, returns a negative integer equivalent to errors from
+ *   glibc.
+ *   -EBADFD : I2C not initialized
+ *   -EBUSY : Device or ressource Busy or Arbitration lost
+ *   -EINVAL : Invalid argument (buf)
+ *   -ENODEV : No such device
+ *   -EREMOTEIO : Device did not acknowledge : Any device present ?
+ *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
+ */
+int tmp101_sensor_read(uint16_t* raw, int* deci_degrees);
+
+
+/* Sensor config
+ * Performs default configuration of the temperature sensor.
+ * The sensor is thus placed in shutdown mode, the thermostat is in interrupt mode,
+ * and the polarity is set to active high.
+ * The conversion resolution is set to the provided "resolution".
+ * RETURN VALUE
+ *   Upon successfull completion, returns 0. On error, returns a negative integer
+ *   equivalent to errors from glibc.
+ *   -EBADFD : I2C not initialized
+ *   -EBUSY : Device or ressource Busy or Arbitration lost
+ *   -EINVAL : Invalid argument (buf)
+ *   -ENODEV : No such device
+ *   -EREMOTEIO : Device did not acknowledge : Any device present ?
+ *   -EIO : Bad one: Illegal start or stop, or illegal state in i2c state machine
+ */
+int tmp101_sensor_config(uint32_t resolution);
+
+/* Start a conversion when the sensor is in shutdown mode. */
+int tmp101_sensor_start_conversion(void);
+
+
+#endif /* EXTDRV_TEMP_H */
+