Hello everyone,
This cc2420 driver is for imote2 platform.It is
far from complete.So,Any suggestion is appreciate.Thanks to Jonathan
Cameron for his help and patience.
It seem that this mail list server does not accept "big" e-mail.My last
e-mail which was 136kb with accessories was rejected by it.So,this time, I
send a "small" one.
From c5771cf11f27e31b8d23ccf187f474804e16d2aa Mon Sep 17 00:00:00 2001
From: liuxue <[email protected]>
Date: Thu, 18 Feb 2010 21:33:37 +0800
Subject: [PATCH] Add cc2420 driver for imote2 platform
---
drivers/ieee802154/Kconfig | 5 +
drivers/ieee802154/Makefile | 1 +
drivers/ieee802154/cc2420.c | 755 +++++++++++++++++++++++++++++++++++++++++++
include/linux/spi/cc2420.h | 198 +++++++++++
4 files changed, 959 insertions(+), 0 deletions(-)
create mode 100644 drivers/ieee802154/cc2420.c
create mode 100644 include/linux/spi/cc2420.h
diff --git a/drivers/ieee802154/Kconfig b/drivers/ieee802154/Kconfig
index a734f21..9b793f9 100644
--- a/drivers/ieee802154/Kconfig
+++ b/drivers/ieee802154/Kconfig
@@ -40,3 +40,8 @@ config IEEE802154_AT86RF230
tristate "AT86RF230 transceiver driver"
depends on SPI
+config IEEE802154_CC2420
+ tristate "CC2420 driver"
+ depends on SPI
+ depends on IEEE802154_DRIVERS
+
diff --git a/drivers/ieee802154/Makefile b/drivers/ieee802154/Makefile
index 76237f3..b54a097 100644
--- a/drivers/ieee802154/Makefile
+++ b/drivers/ieee802154/Makefile
@@ -2,5 +2,6 @@ obj-$(CONFIG_IEEE802154_FAKEHARD) += fakehard.o
obj-$(CONFIG_IEEE802154_FAKELB) += fakelb.o
obj-$(CONFIG_IEEE802154_SERIAL) += serial.o
obj-$(CONFIG_IEEE802154_AT86RF230) += at86rf230.o
+obj-$(CONFIG_IEEE802154_CC2420) += cc2420.o
EXTRA_CFLAGS += -DDEBUG -DCONFIG_FFD
diff --git a/drivers/ieee802154/cc2420.c b/drivers/ieee802154/cc2420.c
new file mode 100644
index 0000000..85cec80
--- /dev/null
+++ b/drivers/ieee802154/cc2420.c
@@ -0,0 +1,755 @@
+/*
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2
+ * as published by the Free Software Foundation.
+ *
+ * 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, write to the Free Software Foundation, Inc.,
+ * 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+ *
+ * Author: Jonathan Cameron <[email protected]>
+ *
+ * Modified 2010: liuxue <[email protected]>
+ */
+
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/mutex.h>
+#include <linux/spinlock.h>
+#include <linux/gpio.h>
+#include <linux/delay.h>
+#include <linux/interrupt.h>
+#include <linux/workqueue.h>
+#include <linux/spi/spi.h>
+#include <linux/spi/cc2420.h>
+#include <linux/skbuff.h>
+#include <linux/irq.h>
+#include <net/mac802154.h>
+#include <net/wpan-phy.h>
+
+#define CC2420_WRITEREG(x) (x)
+#define CC2420_READREG(x) (0x40 | x)
+
+#define CC2420_FREQ_MASK 0x3FF
+#define CC2420_ADR_DECODE_MASK 0x0B00
+#define CC2420_FIFOP_THR_MASK 0x003F
+#define CC2420_CRC_MASK 0x80
+
+#define CC2420_MANFIDLOW 0x233D
+#define CC2420_MANFIDHIGH 0x3000 /* my chip appears to version 3 - broaden this with testing */
+
+// Any good method to replace these functions?
+#define TEST_FIFO_PIN() (GPLR(114) & GPIO_bit(114))
+#define TEST_FIFOP_PIN() (GPLR(0) & GPIO_bit(0))
+#define TEST_CCA_PIN() (GPLR(116) & GPIO_bit(116))
+#define TEST_SFD_PIN() (GPLR(16) & GPIO_bit(16))
+
+#define STATE_PDOWN 0
+#define STATE_IDLE 1
+#define STATE_RX_CALIB 2
+#define STATE_RX_CALIB2 40
+
+#define STATE_RX_SFD_SEARCH_MIN 3
+#define STATE_RX_SFD_SEARCH_MAX 6
+
+struct cc2420_local {
+ struct cc2420_platform_data *pdata;
+ struct spi_device *spi;
+ struct ieee802154_dev *dev;
+ u8 *buf;
+ struct mutex bmux;
+ int fifop_irq;
+ int sfd_irq;
+ struct work_struct fifop_irqwork;
+ struct work_struct sfd_irqwork;
+ spinlock_t lock;
+ unsigned irq_disabled:1;/* P:lock */
+ unsigned is_tx:1; /* P:lock */
+
+ struct completion tx_complete;
+};
+static int cc2420_get_status(struct cc2420_local *lp, u8 *status)
+{
+ int ret;
+ struct spi_message msg;
+ struct spi_transfer xfer = {
+ .len = 1,
+ .tx_buf = lp->buf,
+ .rx_buf = lp->buf,
+ };
+ spi_message_init(&msg);
+ spi_message_add_tail(&xfer, &msg);
+ mutex_lock (&lp->bmux);
+ lp->buf[0] = CC2420_WRITEREG(CC2420_SNOP);
+ dev_vdbg(&lp->spi->dev, "get status command buf[0] = %02x\n", lp->buf[0]);
+ ret = spi_sync(lp->spi, &msg);
+ if (!ret)
+ *status = lp->buf[0];
+ dev_vdbg(&lp->spi->dev, "buf[0] = %02x\n", lp->buf[0]);
+ mutex_unlock(&lp->bmux);
+ return ret;
+
+}
+static int cc2420_cmd_strobe(struct cc2420_local *lp,
+ u8 addr)
+{
+ int ret;
+ u8 status = 0xf;
+ struct spi_message msg;
+ struct spi_transfer xfer = {
+ .len = 1,
+ .tx_buf = lp->buf,
+ .rx_buf = lp->buf,
+ };
+ spi_message_init(&msg);
+ spi_message_add_tail(&xfer, &msg);
+ mutex_lock (&lp->bmux);
+ lp->buf[0] = CC2420_WRITEREG(addr);
+ dev_vdbg(&lp->spi->dev, "cmd strobe buf[0] = %02x\n", lp->buf[0]);
+ ret = spi_sync(lp->spi, &msg);
+ if (!ret)
+ status = lp->buf[0];
+ dev_vdbg(&lp->spi->dev, "buf[0] = %02x\n", lp->buf[0]);
+
+ mutex_unlock(&lp->bmux);
+
+ return ret;
+}
+
+static int cc2420_read_16_bit_reg(struct cc2420_local *lp,
+ u8 addr, u16 *data)
+{
+ int ret;
+ struct spi_message msg;
+ struct spi_transfer xfer = {
+ .len = 3,
+ .tx_buf = lp->buf,
+ .rx_buf = lp->buf,
+ };
+
+ spi_message_init(&msg);
+ spi_message_add_tail(&xfer, &msg);
+ mutex_lock (&lp->bmux);
+ lp->buf[0] = CC2420_READREG(addr);
+ dev_vdbg(&lp->spi->dev, "readreg addr buf[0] = %02x\n", lp->buf[0]);
+ ret = spi_sync(lp->spi, &msg);
+ dev_dbg(&lp->spi->dev, "status = %d\n", ret);
+ mutex_unlock(&lp->bmux);
+ dev_dbg(&lp->spi->dev, "buf[0] = %02x\n", lp->buf[0]);
+ dev_dbg(&lp->spi->dev, "buf[1] = %02x\n", lp->buf[1]);
+ dev_dbg(&lp->spi->dev, "buf[2] = %02x\n", lp->buf[2]);
+ if (!ret)
+ *data = ((u16)(lp->buf[1]) << 8 ) | lp->buf[2];
+ return ret;
+}
+
+static int cc2420_write_16_bit_reg_partial(struct cc2420_local *lp,
+ u8 addr, u16 data, u16 mask)
+{
+ int ret;
+ struct spi_message msg;
+ struct spi_transfer xfer = {
+ .len = 3,
+ .tx_buf = lp->buf,
+ .rx_buf = lp->buf,
+ };
+ printk("data = %x\n", data);
+ printk("mask = %x\n", mask);
+ spi_message_init(&msg);
+ spi_message_add_tail(&xfer, &msg);
+ mutex_lock(&lp->bmux);
+ lp->buf[0] = CC2420_READREG(addr);
+ dev_vdbg(&lp->spi->dev, "read addr buf[0] = %02x\n", lp->buf[0]);
+ ret = spi_sync(lp->spi, &msg);
+ if (ret)
+ goto err_ret;
+ dev_dbg(&lp->spi->dev, "read buf[0] = %02x\n", lp->buf[0]);
+ dev_dbg(&lp->spi->dev, "buf[1] = %02x\n", lp->buf[1]);
+ dev_dbg(&lp->spi->dev, "buf[2] = %02x\n", lp->buf[2]);
+
+ lp->buf[0] = CC2420_WRITEREG(addr);
+
+ //dev_vdbg(&lp->spi->dev, "test: ~(mask >> 8) | (data >> 8) = %x\n", ~(mask >> 8) | (data >> 8));
+ //dev_vdbg(&lp->spi->dev, "test: ~(mask & 0xFF) | (data & 0xFF) = %x\n", ~(mask & 0xFF) | (data & 0xFF));
+ //lp->buf[1] &= ~(mask >> 8) | (data >> 8);
+ //lp->buf[2] &= ~(mask & 0xFF) | (data & 0xFF);
+ lp->buf[1] &= ~(mask >> 8);
+ lp->buf[2] &= ~(mask & 0xFF);
+ lp->buf[1] |= (mask >> 8) & (data >> 8);
+ lp->buf[2] |= (mask & 0xFF) & (data & 0xFF);
+ dev_vdbg(&lp->spi->dev, "writereg addr buf[0] = %02x\n", lp->buf[0]);
+ dev_dbg(&lp->spi->dev, "buf[1] = %02x\n", lp->buf[1]);
+ dev_dbg(&lp->spi->dev, "buf[2] = %02x\n", lp->buf[2]);
+ ret = spi_sync(lp->spi, &msg);
+ if (ret)
+ goto err_ret;
+ dev_dbg(&lp->spi->dev, "return status buf[0] = %02x\n", lp->buf[0]);
+ dev_dbg(&lp->spi->dev, "buf[1] = %02x\n", lp->buf[1]);
+ dev_dbg(&lp->spi->dev, "buf[2] = %02x\n", lp->buf[2]);
+
+err_ret:
+ mutex_unlock(&lp->bmux);
+ return ret;
+}
+
+static int
+cc2420_channel(struct ieee802154_dev *dev, int channel)
+{
+ struct cc2420_local *lp = dev->priv;
+ int ret;
+
+ might_sleep();
+ printk("trying to set channel\n");
+
+ BUG_ON(channel < CC2420_MIN_CHANNEL);
+ BUG_ON(channel > CC2420_MAX_CHANNEL);
+
+ ret = cc2420_write_16_bit_reg_partial(lp, CC2420_FSCTRL, 357 + 5*(channel - 11), CC2420_FREQ_MASK);
+
+ dev->phy->current_channel = channel;
+ return ret;
+}
+
+static int
+cc2420_write_txfifo(struct cc2420_local *lp, u8 *data, u8 len)
+{
+ int status;
+ struct spi_message msg;
+ struct spi_transfer xfer_head = {
+ .len = 1,
+ .tx_buf = lp->buf,
+ .rx_buf = lp->buf,
+ };
+ struct spi_transfer xfer_buf = {
+ .len = len,
+ .tx_buf = data,
+ };
+
+ mutex_lock(&lp->bmux);
+ lp->buf[0] = CC2420_WRITEREG(CC2420_TXFIFO);
+ dev_vdbg(&lp->spi->dev, "TX_FIFO addr buf[0] = %02x\n", lp->buf[0]);
+
+ spi_message_init(&msg);
+ spi_message_add_tail(&xfer_head, &msg);
+ spi_message_add_tail(&xfer_buf, &msg);
+
+ status = spi_sync(lp->spi, &msg);
+ dev_vdbg(&lp->spi->dev, "status = %d\n", status);
+ if (msg.status)
+ status = msg.status;
+ dev_vdbg(&lp->spi->dev, "status = %d\n", status);
+ dev_vdbg(&lp->spi->dev, "buf[0] = %02x\n", lp->buf[0]);
+
+ mutex_unlock(&lp->bmux);
+ return status;
+}
+
+static int
+cc2420_read_rxfifo(struct cc2420_local *lp, u8 *data, u8 *len, u8 *lqi)
+{
+ int status;
+ struct spi_message msg;
+ struct spi_transfer xfer_head = {
+ .len = 2,
+ .tx_buf = lp->buf,
+ .rx_buf = lp->buf,
+ };
+ struct spi_transfer xfer_buf = {
+ .len = *len,
+ .rx_buf = data,
+ };
+
+ mutex_lock(&lp->bmux);
+ lp->buf[0] = CC2420_READREG(CC2420_RXFIFO);
+ lp->buf[1] = 0x00;
+ dev_vdbg(&lp->spi->dev, "read rxfifo buf[0] = %02x\n", lp->buf[0]);
+ dev_vdbg(&lp->spi->dev, "buf[1] = %02x\n", lp->buf[1]);
+ spi_message_init(&msg);
+ spi_message_add_tail(&xfer_head, &msg);
+ spi_message_add_tail(&xfer_buf, &msg);
+
+ status = spi_sync(lp->spi, &msg);
+ dev_vdbg(&lp->spi->dev, "status = %d\n", status);
+ if (msg.status)
+ status = msg.status;
+ dev_vdbg(&lp->spi->dev, "status = %d\n", status);
+ dev_vdbg(&lp->spi->dev, "return status buf[0] = %02x\n", lp->buf[0]);
+ dev_vdbg(&lp->spi->dev, "length buf[1] = %02x\n", lp->buf[1]);
+
+ *lqi = data[lp->buf[1] - 1] & 0x7f;
+ *len = lp->buf[1]; /* it should be less than 130 */
+
+ mutex_unlock(&lp->bmux);
+
+ return status;
+}
+
+
+static int
+cc2420_tx(struct ieee802154_dev *dev, struct sk_buff *skb)
+{
+ struct cc2420_local *lp = dev->priv;
+ int rc;
+ unsigned long flags;
+ u8 status = 0;
+
+ pr_debug("%s\n", __func__);
+
+ might_sleep();
+
+ rc = cc2420_cmd_strobe(lp, CC2420_SFLUSHTX);
+ if (rc)
+ goto err_rx;
+ rc = cc2420_write_txfifo(lp, skb->data, skb->len);
+ if (rc)
+ goto err_rx;
+
+ /* TODO: test CCA pin */
+
+ rc = cc2420_get_status(lp, &status);
+ if (rc) {
+ goto err_rx;
+ }
+ if (status & CC2420_STATUS_TX_UNDERFLOW) {
+ printk("cc2420 tx underflow!\n");
+ goto err_rx;
+ }
+
+ spin_lock_irqsave(&lp->lock, flags);
+ BUG_ON(lp->is_tx);
+ lp->is_tx = 1;
+ INIT_COMPLETION(lp->tx_complete);
+ spin_unlock_irqrestore(&lp->lock, flags);
+
+ rc = cc2420_cmd_strobe(lp, CC2420_STXONCCA);
+ if (rc)
+ goto err;
+
+ rc = wait_for_completion_interruptible(&lp->tx_complete);
+ if (rc < 0)
+ goto err;
+
+ cc2420_cmd_strobe(lp, CC2420_SFLUSHTX);
+ cc2420_cmd_strobe(lp, CC2420_SRXON);
+
+ return rc;
+
+err:
+ spin_lock_irqsave(&lp->lock, flags);
+ lp->is_tx = 0;
+ spin_unlock_irqrestore(&lp->lock, flags);
+err_rx:
+ cc2420_cmd_strobe(lp, CC2420_SFLUSHTX);
+ cc2420_cmd_strobe(lp, CC2420_SRXON);
+ return rc;
+}
+
+static int cc2420_rx(struct cc2420_local *lp)
+{
+ u8 len = 128;
+ u8 lqi = 0; /* link quality */
+ int rc;
+ struct sk_buff *skb;
+
+ skb = alloc_skb(len, GFP_KERNEL);
+ if (!skb)
+ return -ENOMEM;
+
+ rc = cc2420_read_rxfifo(lp, skb_put(skb, len), &len, &lqi);
+ if (len < 2) {
+ kfree_skb(skb);
+ return -EINVAL;
+ }
+
+ skb_trim(skb, len-1); /* We do not put CRC and Corr into
+ the frame,but remain rssi value */
+
+ ieee802154_rx_irqsafe(lp->dev, skb, lqi);
+
+ dev_dbg(&lp->spi->dev, "RXFIFO: %d %d %x\n", rc, len, lqi);
+
+ return 0;
+}
+
+static int
+cc2420_ed(struct ieee802154_dev *dev, u8 *level)
+{
+ printk("ed called\n");
+ *level = 0xbe;
+ return 0;
+}
+
+static int
+cc2420_start(struct ieee802154_dev *dev)
+{
+ return cc2420_cmd_strobe(dev->priv, CC2420_SRXON);
+}
+
+static void
+cc2420_stop(struct ieee802154_dev *dev)
+{
+ cc2420_cmd_strobe(dev->priv, CC2420_SRFOFF);
+}
+
+static struct ieee802154_ops cc2420_ops = {
+ .owner = THIS_MODULE,
+ .xmit = cc2420_tx,
+ .ed = cc2420_ed,
+ .start = cc2420_start,
+ .stop = cc2420_stop,
+ .set_channel = cc2420_channel,
+};
+
+static int cc2420_register(struct cc2420_local *lp)
+{
+ int ret = -ENOMEM;
+ lp->dev = ieee802154_alloc_device(sizeof(*lp), &cc2420_ops);
+ if (!lp->dev)
+ goto err_ret;
+
+ lp->dev->priv = lp;
+ lp->dev->parent = &lp->spi->dev;
+ //look this up.
+ lp->dev->extra_tx_headroom = 0;
+ //and this
+ //lp->dev->channel_mask = 0x7ff;
+ //and more.
+
+ /* We do support only 2.4 Ghz */
+ lp->dev->phy->channels_supported[0] = 0x7FFF800;
+ lp->dev->flags = IEEE802154_HW_OMIT_CKSUM;
+
+ dev_dbg(&lp->spi->dev, "registered cc2420\n");
+ ret = ieee802154_register_device(lp->dev);
+ if (ret)
+ goto err_free_device;
+ return 0;
+err_free_device:
+ ieee802154_free_device(lp->dev);
+err_ret:
+ return ret;
+}
+
+static void cc2420_unregister(struct cc2420_local *lp)
+{
+ ieee802154_unregister_device(lp->dev);
+ //check this is needed
+ ieee802154_free_device(lp->dev);
+}
+
+static irqreturn_t cc2420_isr(int irq, void *data)
+{
+ struct cc2420_local *lp = data;
+ dev_vdbg(&lp->spi->dev, "isr irq pin is pin:%d\n",
+ IRQ_TO_GPIO(irq));
+
+ spin_lock(&lp->lock);
+ if (!lp->irq_disabled) {
+ disable_irq_nosync(irq);
+ lp->irq_disabled = 1;
+ }
+ spin_unlock(&lp->lock);
+
+ /* pin or value? */
+ if (irq == lp->sfd_irq) {
+ schedule_work(&lp->sfd_irqwork);
+ }
+ if (irq == lp->fifop_irq) {
+ schedule_work(&lp->fifop_irqwork);
+ }
+
+ return IRQ_HANDLED;
+}
+
+static void cc2420_fifop_irqwork(struct work_struct *work)
+{
+ struct cc2420_local *lp
+ = container_of(work,struct cc2420_local, fifop_irqwork);
+ unsigned long flags;
+
+ printk("fifop interrupt received\n");
+
+ if (TEST_FIFO_PIN()) {
+ cc2420_rx(lp);
+ }
+ else {
+ dev_vdbg(&lp->spi->dev, "rxfifo overflow\n");
+ }
+
+ cc2420_cmd_strobe(lp, CC2420_SFLUSHRX);
+ cc2420_cmd_strobe(lp, CC2420_SFLUSHRX);
+
+ spin_lock_irqsave(&lp->lock, flags);
+ if (lp->irq_disabled) {
+ lp->irq_disabled = 0;
+ enable_irq(lp->fifop_irq);
+ }
+ spin_unlock_irqrestore(&lp->lock, flags);
+}
+
+static void cc2420_sfd_irqwork(struct work_struct *work)
+{
+ struct cc2420_local *lp
+ = container_of(work,struct cc2420_local, sfd_irqwork);
+ unsigned long flags;
+
+ printk("fifop interrupt received\n");
+
+ spin_lock_irqsave(&lp->lock,flags);
+ if (lp->is_tx) {
+ lp->is_tx = 0;
+ spin_unlock_irqrestore(&lp->lock, flags);
+ complete(&lp->tx_complete);
+ } else {
+ spin_unlock_irqrestore(&lp->lock, flags);
+ }
+
+ spin_lock_irqsave(&lp->lock, flags);
+ if (lp->irq_disabled) {
+ lp->irq_disabled = 0;
+ enable_irq(lp->sfd_irq);
+ }
+ spin_unlock_irqrestore(&lp->lock, flags);
+}
+
+static int cc2420_hw_init(struct cc2420_local *lp)
+{
+ int ret;
+ u16 state;
+ u8 status = 0xff;
+ int timeout = 500; /* 500us delay */
+ ret = cc2420_read_16_bit_reg(lp, CC2420_FSMSTATE, &state);
+ if (ret)
+ goto error_ret;
+ /* reset has occured prior to this, so there should be no other option */
+ if (state != STATE_PDOWN) {
+ ret = -EINVAL;
+ goto error_ret;
+ }
+ ret = cc2420_cmd_strobe(lp, CC2420_SXOSCON);
+ if (ret)
+ goto error_ret;
+
+ do{
+ ret = cc2420_get_status(lp, &status);
+ if(ret)
+ goto error_ret;
+ if (timeout-- <= 0){
+ printk("oscillator start failed!\n");
+ return ret;
+ }
+ udelay(1);
+ }while (!(status & CC2420_STATUS_XOSC16M_STABLE));
+
+ printk("oscillator succesfully brought up \n");
+
+ return 0;
+error_ret:
+ return ret;
+}
+
+static int __devinit cc2420_probe(struct spi_device *spi)
+{
+ int ret;
+ u16 manidl, manidh;
+ struct cc2420_local *lp = kzalloc(sizeof *lp, GFP_KERNEL);
+ if (!lp) {
+ ret = -ENOMEM;
+ goto error_ret;
+ }
+
+ lp->pdata = spi->dev.platform_data;
+ if (!lp->pdata) {
+ dev_err(&spi->dev, "no platform data\n");
+ ret = -EINVAL;
+ goto err_free_local;
+ }
+ spi_set_drvdata(spi, lp);
+ mutex_init(&lp->bmux);
+ INIT_WORK(&lp->fifop_irqwork, cc2420_fifop_irqwork);
+ INIT_WORK(&lp->sfd_irqwork, cc2420_sfd_irqwork);
+ spin_lock_init(&lp->lock);
+ init_completion(&lp->tx_complete);
+
+ lp->spi = spi;
+ lp->buf = kmalloc(3*sizeof *lp->buf, GFP_KERNEL);
+ if (!lp->buf) {
+ ret = -ENOMEM;
+ goto err_free_local;
+ }
+
+ /* Request all the gpio's */
+ ret = gpio_request(lp->pdata->fifo, "fifo");
+ if (ret)
+ goto err_free_buf;
+ ret = gpio_request(lp->pdata->cca, "cca");
+ if (ret)
+ goto err_free_gpio_fifo;
+ /* This is causing problems as fifop is gpio 0 ? */
+ ret = gpio_request(lp->pdata->fifop, "fifop");
+ if (ret)
+ goto err_free_gpio_cca;
+ ret = gpio_request(lp->pdata->sfd, "sfd");
+ if (ret)
+ goto err_free_gpio_fifop;
+ ret = gpio_request(lp->pdata->reset, "reset");
+ if (ret)
+ goto err_free_gpio_sfd;
+ ret = gpio_request(lp->pdata->vreg, "vreg");
+ if (ret)
+ goto err_free_gpio_reset;
+ /* Configure the gpios appropriately */
+
+ /* Enable the voltage regulator */
+ ret = gpio_direction_output(lp->pdata->vreg, 1);
+ if (ret)
+ goto err_free_gpio_reset;
+ udelay(600); /* Time for regulator to power up */
+ /* Toggle the reset */
+ ret = gpio_direction_output(lp->pdata->reset, 0);
+ if (ret)
+ goto err_disable_vreg;
+ udelay(10); /* no idea how long this should be? */
+ ret = gpio_direction_output(lp->pdata->reset, 1);
+ if (ret)
+ goto err_disable_vreg;
+ udelay(10);
+
+ ret = gpio_direction_input(lp->pdata->cca);
+ if (ret)
+ goto err_disable_vreg;
+ ret = gpio_direction_input(lp->pdata->fifo);
+ if (ret)
+ goto err_disable_vreg;
+ ret = gpio_direction_input(lp->pdata->fifop);
+ if (ret)
+ goto err_disable_vreg;
+ ret = gpio_direction_input(lp->pdata->sfd);
+ if (ret)
+ goto err_disable_vreg;
+
+
+ /* Check this is actually a cc2420 */
+ ret = cc2420_read_16_bit_reg(lp, CC2420_MANFIDL, &manidl);
+ if (ret)
+ goto err_free_gpio_vreg;
+ ret = cc2420_read_16_bit_reg(lp, CC2420_MANFIDH, &manidh);
+ if (ret)
+ goto err_free_gpio_vreg;
+ if (manidh != CC2420_MANFIDHIGH || manidl != CC2420_MANFIDLOW) {
+ dev_err(&spi->dev, "Incorrect manufacturer id %x%x\n", manidh, manidl);
+ ret = -ENODEV;
+ goto err_free_gpio_vreg;
+ }
+ /* TODO: make it more readable */
+ printk("Found Chipon CC2420\n");
+ printk("Manufacturer ID:%x Version:%x Partnum:%x\n",
+ manidl & 0x0FFF, manidh >> 12, manidl >> 12);
+
+ ret = cc2420_hw_init(lp);
+ if (ret)
+ goto err_disable_vreg;
+
+ lp->fifop_irq = gpio_to_irq(lp->pdata->fifop);
+ lp->sfd_irq = gpio_to_irq(lp->pdata->sfd);
+
+ ret = request_irq(lp->fifop_irq,
+ cc2420_isr,
+ IRQF_TRIGGER_RISING | IRQF_SHARED,
+ dev_name(&spi->dev),
+ lp);
+ if (ret) {
+ dev_err(&spi->dev, "could not get fifop irq for some reason? \n");
+ goto err_free_fifop_irq;
+ }
+
+ ret = request_irq(lp->sfd_irq,
+ cc2420_isr,
+ IRQF_TRIGGER_FALLING,
+ dev_name(&spi->dev),
+ lp);
+ if (ret) {
+ dev_err(&spi->dev, "could not get sfd irq for some reason? \n");
+ goto err_free_sfd_irq;
+ }
+
+ printk("Close addr decode\n");
+ cc2420_write_16_bit_reg_partial(lp, CC2420_MDMCTRL0, 0, 1 << CC2420_MDMCTRL0_ADRDECODE);
+ printk("Set fifo threshold to 127\n");
+ cc2420_write_16_bit_reg_partial(lp, CC2420_IOCFG0, 127, CC2420_FIFOP_THR_MASK);
+ ret = cc2420_register(lp);
+ if (ret)
+ goto err_free_sfd_irq;
+
+ return 0;
+err_free_sfd_irq:
+ free_irq(gpio_to_irq(lp->pdata->sfd), lp);
+err_free_fifop_irq:
+ free_irq(gpio_to_irq(lp->pdata->fifop), lp);
+err_disable_vreg:
+ gpio_set_value(lp->pdata->vreg, 0);
+err_free_gpio_vreg:
+ gpio_free(lp->pdata->vreg);
+err_free_gpio_reset:
+ gpio_free(lp->pdata->reset);
+err_free_gpio_sfd:
+ gpio_free(lp->pdata->sfd);
+err_free_gpio_fifop:
+ gpio_free(lp->pdata->fifop);
+err_free_gpio_cca:
+ gpio_free(lp->pdata->cca);
+err_free_gpio_fifo:
+ gpio_free(lp->pdata->fifo);
+err_free_buf:
+ kfree(lp->buf);
+err_free_local:
+ kfree(lp);
+error_ret:
+ return ret;
+}
+
+static int __devexit cc2420_remove(struct spi_device *spi)
+{
+ struct cc2420_local *lp = spi_get_drvdata(spi);
+
+ cc2420_unregister(lp);
+ free_irq(gpio_to_irq(lp->pdata->fifop), lp);
+ free_irq(gpio_to_irq(lp->pdata->sfd), lp);
+ gpio_free(lp->pdata->vreg);
+ gpio_free(lp->pdata->reset);
+ gpio_free(lp->pdata->sfd);
+ gpio_free(lp->pdata->fifop);
+ gpio_free(lp->pdata->cca);
+ gpio_free(lp->pdata->fifo);
+ kfree(lp->buf);
+ kfree(lp);
+
+ return 0;
+}
+
+static struct spi_driver cc2420_driver = {
+ .driver = {
+ .name = "cc2420",
+ .owner = THIS_MODULE,
+ },
+ .probe = cc2420_probe,
+ .remove = __devexit_p(cc2420_remove),
+};
+
+static int __init cc2420_init(void)
+{
+ return spi_register_driver(&cc2420_driver);
+}
+module_init(cc2420_init);
+
+static void __exit cc2420_exit(void)
+{
+ spi_unregister_driver(&cc2420_driver);
+}
+module_exit(cc2420_exit);
+MODULE_LICENSE("GPL v2");
diff --git a/include/linux/spi/cc2420.h b/include/linux/spi/cc2420.h
new file mode 100644
index 0000000..aab80c3
--- /dev/null
+++ b/include/linux/spi/cc2420.h
@@ -0,0 +1,198 @@
+/*
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2
+ * as published by the Free Software Foundation.
+ *
+ * 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, write to the Free Software Foundation, Inc.,
+ * 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+ *
+ * Author: Jonathan Cameron <[email protected]>
+ *
+ * Modified 2010: liuxue <[email protected]>
+ */
+
+#ifndef __CC2420_H
+#define __CC2420_H
+struct cc2420_platform_data {
+ int fifo; /* high when bytes in fifo */
+ int cca; /* clear channel assesment */
+ int fifop; /* high when no bytes exceeds some threshold */
+ int sfd; /* high when frame come */
+ int reset;
+ int vreg; /* voltage regulator enable */
+};
+
+enum {
+ CC2420_MIN_CHANNEL = 11,
+ CC2420_MAX_CHANNEL = 26
+};
+
+/* Command strobes */
+#define CC2420_SNOP 0x00 /* no op */
+#define CC2420_SXOSCON 0x01 /* Enable crystal oscillator */
+#define CC2420_STXCAL 0x02
+#define CC2420_SRXON 0x03
+#define CC2420_STXON 0x04
+#define CC2420_STXONCCA 0x05
+#define CC2420_SRFOFF 0x06
+#define CC2420_SXOSCOFF 0x07
+#define CC2420_SFLUSHRX 0x08
+#define CC2420_SFLUSHTX 0x09
+#define CC2420_SACK 0x0A
+#define CC2420_SACKPEND 0x0B
+#define CC2420_SRXDEC 0x0C
+#define CC2420_STXENC 0x0D
+#define CC2420_SAES 0x0E
+
+/* Control registers */
+#define CC2420_MAIN 0x10
+#define CC2420_MDMCTRL0 0x11
+#define CC2420_MDMCTRL1 0x12
+#define CC2420_RSSI 0x13
+#define CC2420_SYNCWORD 0x14
+#define CC2420_TXCTRL 0x15
+#define CC2420_RXCTRL0 0x16
+#define CC2420_RXCTRL1 0x17
+#define CC2420_FSCTRL 0x18
+#define CC2420_SECCTRL0 0x19
+#define CC2420_SECCTRL1 0x1A
+#define CC2420_BATTMON 0x1B
+#define CC2420_IOCFG0 0x1C
+#define CC2420_IOCFG1 0x1D
+#define CC2420_MANFIDL 0x1E /* manufacturer id low */
+#define CC2420_MANFIDH 0x1F /* manufacturer id high */
+#define CC2420_FSMTC 0x20
+#define CC2420_MANAND 0x21
+#define CC2420_MANOR 0x22
+#define CC2420_AGCCTRL 0x23
+#define CC2420_AGCTST0 0x24
+#define CC2420_AGCTST1 0x25
+#define CC2420_AGCTST2 0x26
+#define CC2420_FSTST0 0x27
+#define CC2420_FSTST1 0x28
+#define CC2420_FSTST2 0x29
+#define CC2420_FSTST3 0x2A
+#define CC2420_RXBPFTST 0x2B
+#define CC2420_FSMSTATE 0x2C /* lowest 6 bytes give current state */
+#define CC2420_ADCTST 0x2D
+#define CC2420_DACTST 0x2E
+#define CC2420_TOPTST 0x2F
+#define CC2420_RESERVED 0x30
+#define CC2420_TXFIFO 0x3E
+#define CC2420_RXFIFO 0x3F
+
+#define CC2420_RAM_SHORTADR 0x16A
+#define CC2420_RAM_PANID 0x168
+#define CC2420_RAM_IEEEADR 0x160
+#define CC2420_RAM_CBCSTATE 0x150
+#define CC2420_RAM_TXNONCE 0x140
+#define CC2420_RAM_KEY1 0x130
+#define CC2420_RAM_SABUF 0x120
+#define CC2420_RAM_RXNONCE 0x110
+#define CC2420_RAM_KEY0 0x100
+#define CC2420_RAM_RXFIFO 0x080
+#define CC2420_RAM_TXFIFO 0x000
+
+// MDMCTRL0 Register Bit Positions
+#define CC2420_MDMCTRL0_FRAME 13 // 0 : reject reserved frame types, 1 = accept
+#define CC2420_MDMCTRL0_PANCRD 12 // 0 : not a PAN coordinator
+#define CC2420_MDMCTRL0_ADRDECODE 11 // 1 : enable address decode
+#define CC2420_MDMCTRL0_CCAHIST 8 // 3 bits (8,9,10) : CCA hysteris in db
+#define CC2420_MDMCTRL0_CCAMODE 6 // 2 bits (6,7) : CCA trigger modes
+#define CC2420_MDMCTRL0_AUTOCRC 5 // 1 : generate/chk CRC
+#define CC2420_MDMCTRL0_AUTOACK 4 // 1 : Ack valid packets
+#define CC2420_MDMCTRL0_PREAMBL 0 // 4 bits (0..3): Preamble length
+
+// MDMCTRL1 Register Bit Positions
+#define CC2420_MDMCTRL1_CORRTHRESH 6 // 5 bits (6..10) : correlator threshold
+#define CC2420_MDMCTRL1_DEMOD_MODE 5 // 0: lock freq after preamble match, 1: continous udpate
+#define CC2420_MDMCTRL1_MODU_MODE 4 // 0: IEEE 802.15.4
+#define CC2420_MDMCTRL1_TX_MODE 2 // 2 bits (2,3) : 0: use buffered TXFIFO
+#define CC2420_MDMCTRL1_RX_MODE 0 // 2 bits (0,1) : 0: use buffered RXFIFO
+
+// RSSI Register Bit Positions
+#define CC2420_RSSI_CCA_THRESH 8 // 8 bits (8..15) : 2's compl CCA threshold
+
+// TXCTRL Register Bit Positions
+#define CC2420_TXCTRL_BUFCUR 14 // 2 bits (14,15) : Tx mixer buffer bias current
+#define CC2420_TXCTRL_TURNARND 13 // wait time after STXON before xmit
+#define CC2420_TXCTRL_VAR 11 // 2 bits (11,12) : Varactor array settings
+#define CC2420_TXCTRL_XMITCUR 9 // 2 bits (9,10) : Xmit mixer currents
+#define CC2420_TXCTRL_PACUR 6 // 3 bits (6..8) : PA current
+#define CC2420_TXCTRL_PADIFF 5 // 1: Diff PA, 0: Single ended PA
+#define CC2420_TXCTRL_PAPWR 0 // 5 bits (0..4): Output PA level
+
+// RXCTRL0 Register Bit Positions
+#define CC2420_RXCTRL0_BUFCUR 12 // 2 bits (12,13) : Rx mixer buffer bias current
+#define CC2420_RXCTRL0_HILNAG 10 // 2 bits (10,11) : High gain, LNA current
+#define CC2420_RXCTRL0_MLNAG 8 // 2 bits (8,9) : Med gain, LNA current
+#define CC2420_RXCTRL0_LOLNAG 6 // 2 bits (6,7) : Lo gain, LNA current
+#define CC2420_RXCTRL0_HICUR 4 // 2 bits (4,5) : Main high LNA current
+#define CC2420_RXCTRL0_MCUR 2 // 2 bits (2,3) : Main med LNA current
+#define CC2420_RXCTRL0_LOCUR 0 // 2 bits (0,1) : Main low LNA current
+
+// RXCTRL1 Register Bit Positions
+#define CC2420_RXCTRL1_LOCUR 13 // Ref bias current to Rx bandpass filter
+#define CC2420_RXCTRL1_MIDCUR 12 // Ref bias current to Rx bandpass filter
+#define CC2420_RXCTRL1_LOLOGAIN 11 // LAN low gain mode
+#define CC2420_RXCTRL1_MEDLOGAIN 10 // LAN low gain mode
+#define CC2420_RXCTRL1_HIHGM 9 // Rx mixers, hi gain mode
+#define CC2420_RXCTRL1_MEDHGM 8 // Rx mixers, hi gain mode
+#define CC2420_RXCTRL1_LNACAP 6 // 2 bits (6,7) Selects LAN varactor array setting
+#define CC2420_RXCTRL1_RMIXT 4 // 2 bits (4,5) Receiver mixer output current
+#define CC2420_RXCTRL1_RMIXV 2 // 2 bits (2,3) VCM level, mixer feedback
+#define CC2420_RXCTRL1_RMIXCUR 0 // 2 bits (0,1) Receiver mixer current
+
+// FSCTRL Register Bit Positions
+#define CC2420_FSCTRL_LOCK 14 // 2 bits (14,15) # of clocks for synch
+#define CC2420_FSCTRL_CALDONE 13 // Read only, =1 if cal done since freq synth turned on
+#define CC2420_FSCTRL_CALRUNING 12 // Read only, =1 if cal in progress
+#define CC2420_FSCTRL_LOCKLEN 11 // Synch window pulse width
+#define CC2420_FSCTRL_LOCKSTAT 10 // Read only, = 1 if freq synthesizer is loced
+#define CC2420_FSCTRL_FREQ 0 // 10 bits, set operating frequency
+
+// SECCTRL0 Register Bit Positions
+#define CC2420_SECCTRL0_PROTECT 9 // Protect enable Rx fifo
+#define CC2420_SECCTRL0_CBCHEAD 8 // Define 1st byte of CBC-MAC
+#define CC2420_SECCTRL0_SAKEYSEL 7 // Stand alone key select
+#define CC2420_SECCTRL0_TXKEYSEL 6 // Tx key select
+#define CC2420_SECCTRL0_RXKEYSEL 5 // Rx key select
+#define CC2420_SECCTRL0_SECM 2 // 2 bits (2..4) # of bytes in CBC-MAX auth field
+#define CC2420_SECCTRL0_SECMODE 0 // Security mode
+
+// SECCTRL1 Register Bit Positions
+#define CC2420_SECCTRL1_TXL 8 // 7 bits (8..14) Tx in-line security
+#define CC2420_SECCTRL1_RXL 0 // 7 bits (0..7) Rx in-line security
+
+// BATTMON Register Bit Positions
+#define CC2420_BATTMON_OK 6 // Read only, batter voltage OK
+#define CC2420_BATTMON_EN 5 // Enable battery monitor
+#define CC2420_BATTMON_VOLT 0 // 5 bits (0..4) Battery toggle voltage
+
+// IOCFG0 Register Bit Positions
+#define CC2420_IOCFG0_FIFOPOL 10 // Fifo signal polarity
+#define CC2420_IOCFG0_FIFOPPOL 9 // FifoP signal polarity
+#define CC2420_IOCFG0_SFD 8 // SFD signal polarity
+#define CC2420_IOCFG0_CCAPOL 7 // CCA signal polarity
+#define CC2420_IOCFG0_FIFOTHR 0 // 7 bits, (0..6) # of Rx bytes in fifo to trg fifop
+
+// IOCFG1 Register Bit Positions
+#define CC2420_IOCFG1_HSSD 10 // 2 bits (10,11) HSSD module config
+#define CC2420_IOCFG1_SFDMUX 5 // 5 bits (5..9) SFD multiplexer pin settings
+#define CC2420_IOCFG1_CCAMUX 0 // 5 bits (0..4) CCA multiplexe pin settings
+
+/* Status byte elements */
+#define CC2420_STATUS_XOSC16M_STABLE ( 1 << 6)
+#define CC2420_STATUS_TX_UNDERFLOW (1 << 5)
+#define CC2420_STATUS_ENC_BUSY (1 << 4)
+#define CC2420_STATUS_TX_ACTIVE (1 << 3)
+#define CC2420_STATUS_LOCK (1 << 2)
+#define CC2420_STATUS_RSSI_VALID (1 << 1)
+
+#endif
--
1.6.3.3
------------------------------------------------------------------------------
Download Intel® Parallel Studio Eval
Try the new software tools for yourself. Speed compiling, find bugs
proactively, and fine-tune applications for parallel performance.
See why Intel Parallel Studio got high marks during beta.
http://p.sf.net/sfu/intel-sw-dev
_______________________________________________
Linux-zigbee-devel mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/linux-zigbee-devel