summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-16 15:09:39 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-16 15:09:39 +0000
commit3119f7b909d6c8938ae92e45b1e92dc1bcba0c0b (patch)
treedaf7f588b941cdac94651ca15cc46364c56772f6 /nuttx/drivers
parentc91f7947992488ba67e82f4c56c94cd64d385ffc (diff)
downloadpx4-nuttx-3119f7b909d6c8938ae92e45b1e92dc1bcba0c0b.tar.gz
px4-nuttx-3119f7b909d6c8938ae92e45b1e92dc1bcba0c0b.tar.bz2
px4-nuttx-3119f7b909d6c8938ae92e45b1e92dc1bcba0c0b.zip
Add initial CC1101 wireless logic from Uros
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3617 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/Makefile75
-rw-r--r--nuttx/drivers/bch/Make.defs22
-rwxr-xr-xnuttx/drivers/lcd/Make.defs18
-rw-r--r--nuttx/drivers/mmcsd/Make.defs14
-rw-r--r--nuttx/drivers/mtd/Make.defs13
-rw-r--r--nuttx/drivers/net/Make.defs27
-rw-r--r--nuttx/drivers/pipes/Make.defs15
-rw-r--r--nuttx/drivers/sensors/Make.defs11
-rw-r--r--nuttx/drivers/sensors/lis331dl.c4
-rw-r--r--nuttx/drivers/serial/Make.defs16
-rw-r--r--nuttx/drivers/usbdev/Make.defs23
-rw-r--r--nuttx/drivers/usbhost/Make.defs24
-rw-r--r--nuttx/drivers/wireless/Make.defs14
-rwxr-xr-xnuttx/drivers/wireless/cc1101.c514
-rw-r--r--nuttx/drivers/wireless/cc1101/ISM1_868MHzGFSK100kbps.c113
-rw-r--r--nuttx/drivers/wireless/cc1101/ISM2_905MHzGFSK250kbps.c111
-rwxr-xr-xnuttx/drivers/wireless/cc1101/cc1101.c773
17 files changed, 1149 insertions, 638 deletions
diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
index 7bc8c6912..c46046bb7 100644
--- a/nuttx/drivers/Makefile
+++ b/nuttx/drivers/Makefile
@@ -39,79 +39,35 @@ ifeq ($(WINTOOL),y)
INCDIROPT = -w
endif
-ROOTDEPPATH = --dep-path .
+DEPPATH = --dep-path .
+ASRCS =
+CSRCS =
+VPATH = .
-ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
-include serial/Make.defs
-SERIALDEPPATH = --dep-path serial
-endif
+# Include support for various drivers. Each Make.defs file will add its
+# files to the source file list, add its DEPPATH info, and will add
+# the appropriate paths to the VPATH variable
-ifeq ($(CONFIG_NET),y)
+include serial/Make.defs
include net/Make.defs
-NETDEPPATH = --dep-path net
-endif
-
-ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
include pipes/Make.defs
-PIPEDEPPATH = --dep-path pipes
-endif
-
-ifeq ($(CONFIG_USBDEV),y)
include usbdev/Make.defs
-USBDEVDEPPATH = --dep-path usbdev
-CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbdev}
-endif
-
-ifeq ($(CONFIG_USBHOST),y)
include usbhost/Make.defs
-USBHOSTDEPPATH = --dep-path usbhost
-CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbhost}
-endif
-
include mmcsd/Make.defs
-MMCSDDEPPATH = --dep-path mmcsd
-CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/mmcsd}
-
include lcd/Make.defs
-LCDDEPPATH = --dep-path lcd
-CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/lcd}
-
-ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
-ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y)
include bch/Make.defs
-BCHDEPPATH = --dep-path bch
-CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/bch}
-endif
-endif
-
include mtd/Make.defs
-MTDDEPPATH = --dep-path mtd
-
include sensors/Make.defs
-SENSORSDEPPATH = --dep-path sensors
-CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/sensors}
-
-ifeq ($(CONFIG_WIRELESS),y)
include wireless/Make.defs
-WIRELESSDEPPATH = --dep-path wireless
-CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/wireless}
-endif
-
-ASRCS = $(SERIAL_ASRCS) $(NET_ASRCS) $(PIPE_ASRCS) $(USBDEV_ASRCS) \
- $(USBHOST_ASRCS) $(MMCSD_ASRCS) $(LCD_ASRCS) $(BCH_ASRCS) \
- $(MTD_ASRCS) $(SENSOR_ASRCS) $(WIRELESS_ASRCS)
-AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS =
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
-CSRCS += dev_null.c dev_zero.c loop.c can.c
+ CSRCS += dev_null.c dev_zero.c loop.c can.c
ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y)
-CSRCS += ramdisk.c rwbuffer.c
+ CSRCS += ramdisk.c rwbuffer.c
endif
endif
-CSRCS += $(SERIAL_CSRCS) $(NET_CSRCS) $(PIPE_CSRCS) $(USBDEV_CSRCS) \
- $(USBHOST_CSRCS) $(MMCSD_CSRCS) $(LCD_CSRCS) $(BCH_CSRCS) \
- $(MTD_CSRCS) $(SENSOR_CSRCS) $(WIRELESS_CSRCS)
+
+AOBJS = $(ASRCS:.S=$(OBJEXT))
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
@@ -119,8 +75,6 @@ OBJS = $(AOBJS) $(COBJS)
BIN = libdrivers$(LIBEXT)
-VPATH = serial:net:pipes:usbdev:usbhost:mmcsd:lcd:bch:mtd:sensors:wireless
-
all: $(BIN)
$(AOBJS): %$(OBJEXT): %.S
@@ -135,10 +89,7 @@ $(BIN): $(OBJS)
done ; )
.depend: Makefile $(SRCS)
- @$(MKDEP) $(ROOTDEPPATH) $(SERIALDEPPATH) $(NETDEPPATH) $(PIPEDEPPATH) \
- $(USBDEVDEPPATH) $(USBHOSTDEPPATH) $(MMCSDDEPPATH) $(LCDDEPPATH) \
- $(BCHDEPPATH) $(MTDDEPPATH) $(SENSORSDEPPATH) $(WIRELESSDEPPATH) \
- $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @$(MKDEP) $(DEPPATH) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
@touch $@
depend: .depend
diff --git a/nuttx/drivers/bch/Make.defs b/nuttx/drivers/bch/Make.defs
index efbfbe2bc..8dc36b8c4 100644
--- a/nuttx/drivers/bch/Make.defs
+++ b/nuttx/drivers/bch/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# drivers/bch/Make.defs
#
-# Copyright (C) 2008 Gregory Nutt. All rights reserved.
+# Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -33,8 +33,20 @@
#
############################################################################
-BCH_ASRCS =
-BCH_CSRCS = bchlib_setup.c bchlib_teardown.c bchlib_read.c bchlib_write.c \
- bchlib_cache.c bchlib_sem.c bchdev_register.c bchdev_unregister.c \
- bchdev_driver.c
+ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
+ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y)
+# Include BCH driver
+
+CSRCS += bchlib_setup.c bchlib_teardown.c bchlib_read.c bchlib_write.c \
+ bchlib_cache.c bchlib_sem.c bchdev_register.c bchdev_unregister.c \
+ bchdev_driver.c
+
+# Include BCH driver build support
+
+DEPPATH += --dep-path bch
+VPATH += :bch
+CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/bch}
+
+endif
+endif
diff --git a/nuttx/drivers/lcd/Make.defs b/nuttx/drivers/lcd/Make.defs
index 5c9198a8f..596cce7d5 100755
--- a/nuttx/drivers/lcd/Make.defs
+++ b/nuttx/drivers/lcd/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# drivers/lcd/Make.defs
#
-# Copyright (C) 2010 Gregory Nutt. All rights reserved.
+# Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -33,24 +33,28 @@
#
############################################################################
-LCD_ASRCS =
-LCD_CSRCS =
-
# Don't build anything if there is no NX support for LCD drivers
ifeq ($(CONFIG_NX_LCDDRIVER),y)
+# Include LCD drivers
+
ifeq ($(CONFIG_LCD_P14201),y)
- LCD_CSRCS = p14201.c
+ CSRCS += p14201.c
endif
ifeq ($(CONFIG_LCD_NOKIA6100),y)
- LCD_CSRCS = nokia6100.c
+ CSRCS += nokia6100.c
endif
ifeq ($(CONFIG_LCD_UG9664HSWAG01),y)
- LCD_CSRCS = ug-9664hswag01.c
+ CSRCS += ug-9664hswag01.c
endif
+# Include LCD driver build support
+
+DEPPATH += --dep-path lcd
+VPATH += :lcd
+CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/lcd}
endif
diff --git a/nuttx/drivers/mmcsd/Make.defs b/nuttx/drivers/mmcsd/Make.defs
index 6e7bf8080..48e5d4fb6 100644
--- a/nuttx/drivers/mmcsd/Make.defs
+++ b/nuttx/drivers/mmcsd/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# drivers/mmcsd/Make.defs
#
-# Copyright (C) 2008 Gregory Nutt. All rights reserved.
+# Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -33,6 +33,14 @@
#
############################################################################
-MMCSD_ASRCS =
-MMCSD_CSRCS = mmcsd_sdio.c mmcsd_spi.c mmcsd_debug.c
+# Include MMC/SD drivers
+
+CSRCS += mmcsd_sdio.c mmcsd_spi.c mmcsd_debug.c
+
+# Include MMC/SD driver build support
+
+DEPPATH += --dep-path mmcsd
+VPATH += :mmcsd
+CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/mmcsd}
+
diff --git a/nuttx/drivers/mtd/Make.defs b/nuttx/drivers/mtd/Make.defs
index ab214a36e..58870521b 100644
--- a/nuttx/drivers/mtd/Make.defs
+++ b/nuttx/drivers/mtd/Make.defs
@@ -2,7 +2,7 @@
# drivers/mtd/Make.defs
# This driver supports a block of RAM as a NuttX MTD device
#
-# Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+# Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -34,5 +34,12 @@
#
############################################################################
-MTD_ASRCS =
-MTD_CSRCS = ftl.c m25px.c at45db.c ramtron.c rammtd.c
+# Include MTD drivers
+
+CSRCS += ftl.c m25px.c at45db.c ramtron.c rammtd.c
+
+# Include MTD driver support
+
+DEPPATH += --dep-path mtd
+VPATH += :mtd
+
diff --git a/nuttx/drivers/net/Make.defs b/nuttx/drivers/net/Make.defs
index f3b9d2645..eba3e5078 100644
--- a/nuttx/drivers/net/Make.defs
+++ b/nuttx/drivers/net/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# drivers/net/Make.defs
#
-# Copyright (C) 2007, 2010 Gregory Nutt. All rights reserved.
+# Copyright (C) 2007, 2010-2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -33,24 +33,35 @@
#
############################################################################
-NET_ASRCS =
-NET_CSRCS =
+# Include nothing if networking is disabled
ifeq ($(CONFIG_NET),y)
+
+# Include network interface drivers
+
ifeq ($(CONFIG_NET_DM90x0),y)
-NET_CSRCS += dm90x0.c
+ CSRCS += dm90x0.c
endif
+
ifeq ($(CONFIG_NET_CS89x0),y)
-NET_CSRCS += cs89x0.c
+ CSRCS += cs89x0.c
endif
+
ifeq ($(CONFIG_NET_ENC28J60),y)
-NET_CSRCS += enc28j60.c
+ CSRCS += enc28j60.c
endif
+
ifeq ($(CONFIG_NET_VNET),y)
-NET_CSRCS += vnet.c
+ CSRCS += vnet.c
endif
+
ifeq ($(CONFIG_NET_SLIP),y)
-NET_CSRCS += slip.c
+ CSRCS += slip.c
endif
+
+# Include network build support
+
+DEPPATH += --dep-path net
+VPATH += :net
endif
diff --git a/nuttx/drivers/pipes/Make.defs b/nuttx/drivers/pipes/Make.defs
index be16366bb..15930627a 100644
--- a/nuttx/drivers/pipes/Make.defs
+++ b/nuttx/drivers/pipes/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# drivers/pipes/Make.defs
#
-# Copyright (C) 2009 Gregory Nutt. All rights reserved.
+# Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -33,9 +33,14 @@
#
############################################################################
-PIPE_ASRCS =
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
-PIPE_CSRCS = pipe.c fifo.c pipe_common.c
-else
-PIPE_CSRCS =
+
+# Include pipe driver
+
+CSRCS += pipe.c fifo.c pipe_common.c
+
+# Include pipe build support
+
+DEPPATH += --dep-path pipes
+VPATH += :pipes
endif
diff --git a/nuttx/drivers/sensors/Make.defs b/nuttx/drivers/sensors/Make.defs
index d1019dd4d..1b3c3de03 100644
--- a/nuttx/drivers/sensors/Make.defs
+++ b/nuttx/drivers/sensors/Make.defs
@@ -33,12 +33,15 @@
#
############################################################################
-SENSOR_ASRCS =
-SENSOR_CSRCS =
-
+# Include sensor drivers
# These drivers depend on I2C support
ifeq ($(CONFIG_I2C),y)
-SENSOR_CSRCS += lis331dl.c
+ CSRCS += lis331dl.c
endif
+# Include sensor driver build support
+
+DEPPATH += --dep-path sensors
+VPATH += :sensors
+CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/sensors}
diff --git a/nuttx/drivers/sensors/lis331dl.c b/nuttx/drivers/sensors/lis331dl.c
index 4f8a858ab..2117a7ebd 100644
--- a/nuttx/drivers/sensors/lis331dl.c
+++ b/nuttx/drivers/sensors/lis331dl.c
@@ -189,8 +189,10 @@ struct lis331dl_dev_s * lis331dl_init(struct i2c_dev_s * i2c, uint16_t address)
ASSERT(i2c);
ASSERT(address);
- if ( (dev = kmalloc( sizeof(struct lis331dl_dev_s) )) == NULL )
+ if ( (dev = kmalloc( sizeof(struct lis331dl_dev_s) )) == NULL ) {
+ errno = ENOMEM;
return NULL;
+ }
memset(dev, 0, sizeof(struct lis331dl_dev_s));
dev->i2c = i2c;
diff --git a/nuttx/drivers/serial/Make.defs b/nuttx/drivers/serial/Make.defs
index 7799233db..b78628334 100644
--- a/nuttx/drivers/serial/Make.defs
+++ b/nuttx/drivers/serial/Make.defs
@@ -33,12 +33,18 @@
#
############################################################################
-SERIAL_ASRCS =
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
-SERIAL_CSRCS = serial.c serialirq.c lowconsole.c
+
+# Include serial drivers
+
+CSRCS += serial.c serialirq.c lowconsole.c
+
ifeq ($(CONFIG_16550_UART),y)
-SERIAL_CSRCS += uart_16550.c
+ CSRCS += uart_16550.c
endif
-else
-SERIAL_CSRCS =
+
+# Include serial build support
+
+DEPPATH += --dep-path serial
+VPATH += :serial
endif
diff --git a/nuttx/drivers/usbdev/Make.defs b/nuttx/drivers/usbdev/Make.defs
index 32dd96f8d..2a1c51625 100644
--- a/nuttx/drivers/usbdev/Make.defs
+++ b/nuttx/drivers/usbdev/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# drivers/usbdev/Make.defs
#
-# Copyright (C) 2008, 2010 Gregory Nutt. All rights reserved.
+# Copyright (C) 2008, 2010-2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -33,16 +33,23 @@
#
############################################################################
-USBDEV_ASRCS =
-USBDEV_CSRCS =
-
ifeq ($(CONFIG_USBDEV),y)
+
+# Include USB device drivers
+
ifeq ($(CONFIG_USBSER),y)
-USBDEV_CSRCS += usbdev_serial.c
+ CSRCS += usbdev_serial.c
endif
+
ifeq ($(CONFIG_USBSTRG),y)
-USBDEV_CSRCS += usbdev_storage.c usbdev_scsi.c
-endif
-USBDEV_CSRCS += usbdev_trace.c usbdev_trprintf.c
+ CSRCS += usbdev_storage.c usbdev_scsi.c
endif
+CSRCS += usbdev_trace.c usbdev_trprintf.c
+
+# Include USB device build support
+
+DEPPATH += --dep-path usbdev
+VPATH += :usbdev
+CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbdev}
+endif
diff --git a/nuttx/drivers/usbhost/Make.defs b/nuttx/drivers/usbhost/Make.defs
index ffdb9c651..cc28e874d 100644
--- a/nuttx/drivers/usbhost/Make.defs
+++ b/nuttx/drivers/usbhost/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# drivers/usbhost/Make.defs
#
-# Copyright (C) 2010 Gregory Nutt. All rights reserved.
+# Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
@@ -33,19 +33,25 @@
#
############################################################################
-USBHOST_ASRCS =
-USBHOST_CSRCS = hid_parser.c
-
-# Built-in USB driver logic
+CSRCS += hid_parser.c
ifeq ($(CONFIG_USBHOST),y)
-USBHOST_CSRCS += usbhost_registry.c usbhost_registerclass.c usbhost_findclass.c
-USBHOST_CSRCS += usbhost_enumerate.c usbhost_storage.c usbhost_hidkbd.c
-# Add-on USB driver logic (see misc/drivers)
+# Include built-in USB host driver logic
+
+CSRCS += usbhost_registry.c usbhost_registerclass.c usbhost_findclass.c
+CSRCS += usbhost_enumerate.c usbhost_storage.c usbhost_hidkbd.c
+
+# Include add-on USB host driver logic (see misc/drivers)
ifeq ($(CONFIG_NET),y)
RTL8187_CSRC := ${shell if [ -f usbhost/rtl8187x.c ]; then echo "rtl8187x.c"; fi}
- USBHOST_CSRCS += $(RTL8187_CSRC)
+ CSRCS += $(RTL8187_CSRC)
endif
endif
+
+# Include USB host driver build logic
+
+DEPPATH += --dep-path usbhost
+VPATH += :usbhost
+CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/usbhost}
diff --git a/nuttx/drivers/wireless/Make.defs b/nuttx/drivers/wireless/Make.defs
index 0e1aae550..ac73c8d85 100644
--- a/nuttx/drivers/wireless/Make.defs
+++ b/nuttx/drivers/wireless/Make.defs
@@ -33,9 +33,15 @@
#
############################################################################
-WIRELESS_ASRCS =
-WIRELESS_CSRCS =
-
ifeq ($(CONFIG_WIRELESS),y)
-WIRELESS_CSRCS += cc1101.c
+
+# Include wireless drivers
+
+CSRCS += cc1101.c ISM1_868MHzGFSK100kbps.c ISM2_905MHzGFSK250kbps.c
+
+# Include wireless build support
+
+DEPPATH += --dep-path wireless/cc1101
+VPATH += :wireless/cc1101
+CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/drivers/wireless/cc1101}
endif
diff --git a/nuttx/drivers/wireless/cc1101.c b/nuttx/drivers/wireless/cc1101.c
deleted file mode 100755
index 0d8c003c6..000000000
--- a/nuttx/drivers/wireless/cc1101.c
+++ /dev/null
@@ -1,514 +0,0 @@
-/****************************************************************************
- * drivers/wireless/cc1101.c
- *
- * Copyright (C) 2011 Uros Platise. All rights reserved.
- *
- * Authors: Uros Platise <uros.platise@isotel.eu>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/** \file
- * \author Uros Platise
- * \brief Chipcon CC1101 Device Driver
- *
- *
- **/
-
-#include <nuttx/config.h>
-#include <assert.h>
-#include <stdlib.h>
-#include <string.h>
-#include <errno.h>
-#include <stdio.h>
-
-#include <nuttx/kmalloc.h>
-#include <nuttx/wireless/cc1101.h>
-
-
-/************************************************************************************
- * Chipcon CC1101 Internal Registers
- ************************************************************************************/
-
-/* Configuration Registers */
-
-#define CC1101_IOCFG2 0x00 /* GDO2 output pin configuration */
-#define CC1101_IOCFG1 0x01 /* GDO1 output pin configuration */
-#define CC1101_IOCFG0 0x02 /* GDO0 output pin configuration */
-#define CC1101_FIFOTHR 0x03 /* RX FIFO and TX FIFO thresholds */
-#define CC1101_SYNC1 0x04 /* Sync word, high byte */
-#define CC1101_SYNC0 0x05 /* Sync word, low byte */
-#define CC1101_PKTLEN 0x06 /* Packet length */
-#define CC1101_PKTCTRL1 0x07 /* Packet automation control */
-#define CC1101_PKTCTRL0 0x08 /* Packet automation control */
-#define CC1101_ADDR 0x09 /* Device address */
-#define CC1101_CHANNR 0x0A /* Channel number */
-#define CC1101_FSCTRL1 0x0B /* Frequency synthesizer control */
-#define CC1101_FSCTRL0 0x0C /* Frequency synthesizer control */
-#define CC1101_FREQ2 0x0D /* Frequency control word, high byte */
-#define CC1101_FREQ1 0x0E /* Frequency control word, middle byte */
-#define CC1101_FREQ0 0x0F /* Frequency control word, low byte */
-#define CC1101_MDMCFG4 0x10 /* Modem configuration */
-#define CC1101_MDMCFG3 0x11 /* Modem configuration */
-#define CC1101_MDMCFG2 0x12 /* Modem configuration */
-#define CC1101_MDMCFG1 0x13 /* Modem configuration */
-#define CC1101_MDMCFG0 0x14 /* Modem configuration */
-#define CC1101_DEVIATN 0x15 /* Modem deviation setting */
-#define CC1101_MCSM2 0x16 /* Main Radio Cntrl State Machine config */
-#define CC1101_MCSM1 0x17 /* Main Radio Cntrl State Machine config */
-#define CC1101_MCSM0 0x18 /* Main Radio Cntrl State Machine config */
-#define CC1101_FOCCFG 0x19 /* Frequency Offset Compensation config */
-#define CC1101_BSCFG 0x1A /* Bit Synchronization configuration */
-#define CC1101_AGCCTRL2 0x1B /* AGC control */
-#define CC1101_AGCCTRL1 0x1C /* AGC control */
-#define CC1101_AGCCTRL0 0x1D /* AGC control */
-#define CC1101_WOREVT1 0x1E /* High byte Event 0 timeout */
-#define CC1101_WOREVT0 0x1F /* Low byte Event 0 timeout */
-#define CC1101_WORCTRL 0x20 /* Wake On Radio control */
-#define CC1101_FREND1 0x21 /* Front end RX configuration */
-#define CC1101_FREND0 0x22 /* Front end TX configuration */
-#define CC1101_FSCAL3 0x23 /* Frequency synthesizer calibration */
-#define CC1101_FSCAL2 0x24 /* Frequency synthesizer calibration */
-#define CC1101_FSCAL1 0x25 /* Frequency synthesizer calibration */
-#define CC1101_FSCAL0 0x26 /* Frequency synthesizer calibration */
-#define CC1101_RCCTRL1 0x27 /* RC oscillator configuration */
-#define CC1101_RCCTRL0 0x28 /* RC oscillator configuration */
-#define CC1101_FSTEST 0x29 /* Frequency synthesizer cal control */
-#define CC1101_PTEST 0x2A /* Production test */
-#define CC1101_AGCTEST 0x2B /* AGC test */
-#define CC1101_TEST2 0x2C /* Various test settings */
-#define CC1101_TEST1 0x2D /* Various test settings */
-#define CC1101_TEST0 0x2E /* Various test settings */
-
-/* Status registers */
-
-#define CC1101_PARTNUM (0x30 | 0xc0) /* Part number */
-#define CC1101_VERSION (0x31 | 0xc0) /* Current version number */
-#define CC1101_FREQEST (0x32 | 0xc0) /* Frequency offset estimate */
-#define CC1101_LQI (0x33 | 0xc0) /* Demodulator estimate for link quality */
-#define CC1101_RSSI (0x34 | 0xc0) /* Received signal strength indication */
-#define CC1101_MARCSTATE (0x35 | 0xc0) /* Control state machine state */
-#define CC1101_WORTIME1 (0x36 | 0xc0) /* High byte of WOR timer */
-#define CC1101_WORTIME0 (0x37 | 0xc0) /* Low byte of WOR timer */
-#define CC1101_PKTSTATUS (0x38 | 0xc0) /* Current GDOx status and packet status */
-#define CC1101_VCO_VC_DAC (0x39 | 0xc0) /* Current setting from PLL cal module */
-#define CC1101_TXBYTES (0x3A | 0xc0) /* Underflow and # of bytes in TXFIFO */
-#define CC1101_RXBYTES (0x3B | 0xc0) /* Overflow and # of bytes in RXFIFO */
-#define CC1101_RCCTRL1_STATUS (0x3E | 0xc0) /* Last RC oscilator calibration results */
-#define CC1101_RCCTRL0_STATUS (0x3F | 0xc0) /* Last RC oscilator calibration results */
-
-/* Multi byte memory locations */
-
-#define CC1101_PATABLE 0x3E
-#define CC1101_TXFIFO 0x3F
-#define CC1101_RXFIFO 0x3F
-
-/* Definitions for burst/single access to registers */
-
-#define CC1101_WRITE_BURST 0x40
-#define CC1101_READ_SINGLE 0x80
-#define CC1101_READ_BURST 0xC0
-
-/* Strobe commands */
-
-#define CC1101_SRES 0x30 /* Reset chip. */
-#define CC1101_SFSTXON 0x31 /* Enable and calibrate frequency synthesizer (if MCSM0.FS_AUTOCAL=1). */
-#define CC1101_SXOFF 0x32 /* Turn off crystal oscillator. */
-#define CC1101_SCAL 0x33 /* Calibrate frequency synthesizer and turn it off */
-#define CC1101_SRX 0x34 /* Enable RX. Perform calibration first if switching from IDLE and MCSM0.FS_AUTOCAL=1. */
-#define CC1101_STX 0x35 /* Enable TX. Perform calibration first if IDLE and MCSM0.FS_AUTOCAL=1. */
- /* If switching from RX state and CCA is enabled then go directly to TX if channel is clear. */
-#define CC1101_SIDLE 0x36 /* Exit RX / TX, turn off frequency synthesizer and exit Wake-On-Radio mode if applicable. */
-#define CC1101_SAFC 0x37 /* Perform AFC adjustment of the frequency synthesizer */
-#define CC1101_SWOR 0x38 /* Start automatic RX polling sequence (Wake-on-Radio) */
-#define CC1101_SPWD 0x39 /* Enter power down mode when CSn goes high. */
-#define CC1101_SFRX 0x3A /* Flush the RX FIFO buffer. */
-#define CC1101_SFTX 0x3B /* Flush the TX FIFO buffer. */
-#define CC1101_SWORRST 0x3C /* Reset real time clock. */
-#define CC1101_SNOP 0x3D /* No operation. */
-
-/*
- * Chip Status Byte
- */
-
-/* Bit fields in the chip status byte */
-
-#define CC1101_STATUS_CHIP_RDYn_BM 0x80
-#define CC1101_STATUS_STATE_BM 0x70
-#define CC1101_STATUS_FIFO_BYTES_AVAILABLE_BM 0x0F
-
-/* Chip states */
-
-#define CC1101_STATE_IDLE 0x00
-#define CC1101_STATE_RX 0x10
-#define CC1101_STATE_TX 0x20
-#define CC1101_STATE_FSTXON 0x30
-#define CC1101_STATE_CALIBRATE 0x40
-#define CC1101_STATE_SETTLING 0x50
-#define CC1101_STATE_RX_OVERFLOW 0x60
-#define CC1101_STATE_TX_UNDERFLOW 0x70
-
-/* Values of the MACRSTATE register */
-
-#define CC1101_MARCSTATE_SLEEP 0x00
-#define CC1101_MARCSTATE_IDLE 0x01
-#define CC1101_MARCSTATE_XOFF 0x02
-#define CC1101_MARCSTATE_VCOON_MC 0x03
-#define CC1101_MARCSTATE_REGON_MC 0x04
-#define CC1101_MARCSTATE_MANCAL 0x05
-#define CC1101_MARCSTATE_VCOON 0x06
-#define CC1101_MARCSTATE_REGON 0x07
-#define CC1101_MARCSTATE_STARTCAL 0x08
-#define CC1101_MARCSTATE_BWBOOST 0x09
-#define CC1101_MARCSTATE_FS_LOCK 0x0A
-#define CC1101_MARCSTATE_IFADCON 0x0B
-#define CC1101_MARCSTATE_ENDCAL 0x0C
-#define CC1101_MARCSTATE_RX 0x0D
-#define CC1101_MARCSTATE_RX_END 0x0E
-#define CC1101_MARCSTATE_RX_RST 0x0F
-#define CC1101_MARCSTATE_TXRX_SWITCH 0x10
-#define CC1101_MARCSTATE_RXFIFO_OVERFLOW 0x11
-#define CC1101_MARCSTATE_FSTXON 0x12
-#define CC1101_MARCSTATE_TX 0x13
-#define CC1101_MARCSTATE_TX_END 0x14
-#define CC1101_MARCSTATE_RXTX_SWITCH 0x15
-#define CC1101_MARCSTATE_TXFIFO_UNDERFLOW 0x16
-
-
-/*
- * General Purpose, Test Output Pin Options
- */
-
-/* Associated to the RX FIFO: Asserts when RX FIFO is filled at or above
- * the RX FIFO threshold. De-asserts when RX FIFO is drained below the
- * same threshold. */
-#define CC1101_GDO_RXFIFO_THR 0x00
-
-/* Associated to the RX FIFO: Asserts when RX FIFO is filled at or above
- * the RX FIFO threshold or the end of packet is reached. De-asserts when
- * the RX FIFO is empty. */
-#define CC1101_GDO_RXFIFO_THREND 0x01
-
-/* Associated to the TX FIFO: Asserts when the TX FIFO is filled at or
- * above the TX FIFO threshold. De-asserts when the TX FIFO is below the
- * same threshold. */
-#define CC1101_GDO_TXFIFO_THR 0x02
-
-/* Associated to the TX FIFO: Asserts when TX FIFO is full. De-asserts
- * when the TX FIFO is drained below theTX FIFO threshold. */
-#define CC1101_GDO_TXFIFO_FULL 0x03
-
-/* Asserts when the RX FIFO has overflowed. De-asserts when the FIFO has
- * been flushed. */
-#define CC1101_GDO_RXFIFO_OVR 0x04
-
-/* Asserts when the TX FIFO has underflowed. De-asserts when the FIFO is
- * flushed. */
-#define CC1101_GDO_TXFIFO_UNR 0x05
-
-/* Asserts when sync word has been sent / received, and de-asserts at the
- * end of the packet. In RX, the pin will de-assert when the optional
- * address check fails or the RX FIFO overflows. In TX the pin will
- * de-assert if the TX FIFO underflows. */
-#define CC1101_GDO_SYNC 0x06
-
-/* Asserts when a packet has been received with CRC OK. De-asserts when
- * the first byte is read from the RX FIFO. */
-#define CC1101_GDO_CRCOK 0x07
-
-/* Preamble Quality Reached. Asserts when the PQI is above the programmed
- * PQT value. */
-#define CC1101_GDO_PREAMBLE 0x08
-
-/* Clear channel assessment. High when RSSI level is below threshold
- * (dependent on the current CCA_MODE setting). */
-#define CC1101_GDO_CHCLEAR 0x09
-
-/* Lock detector output. The PLL is in lock if the lock detector output
- * has a positive transition or is constantly logic high. To check for
- * PLL lock the lock detector output should be used as an interrupt for
- * the MCU. */
-#define CC1101_GDO_LOCK 0x0A
-
-/* Serial Clock. Synchronous to the data in synchronous serial mode.
- * In RX mode, data is set up on the falling edge by CC1101 when GDOx_INV=0.
- * In TX mode, data is sampled by CC1101 on the rising edge of the serial
- * clock when GDOx_INV=0. */
-#define CC1101_GDO_SSCLK 0x0B
-
-/* Serial Synchronous Data Output. Used for synchronous serial mode. */
-#define CC1101_GDO_SSDO 0x0C
-
-/* Serial Data Output. Used for asynchronous serial mode. */
-#define CC1101_GDO_ASDO 0x0D
-
-/* Carrier sense. High if RSSI level is above threshold. */
-#define CC1101_GDO_CARRIER 0x0E
-
-/* CRC_OK. The last CRC comparison matched. Cleared when entering or
- * restarting RX mode. */
-#define CC1101_GDO_CRCOK2 0x0F
-
-/* RX_HARD_DATA[1]. Can be used together with RX_SYMBOL_TICK for
- * alternative serial RX output. */
-#define CC1101_GDO_RXOUT1 0x16
-
-/* RX_HARD_DATA[0]. Can be used together with RX_SYMBOL_TICK for
- * alternative serial RX output. */
-#define CC1101_GDO_RXOUT0 0x17
-
-/* PA_PD. Note: PA_PD will have the same signal level in SLEEP and TX
- * states. To control an external PA or RX/TX switch in applications
- * where the SLEEP state is used it is recommended to use GDOx_CFGx=0x2F
- * instead. */
-#define CC1101_GDO_PA_PD 0x1B
-
-/* LNA_PD. Note: LNA_PD will have the same signal level in SLEEP and RX
- * states. To control an external LNA or RX/TX switch in applications
- * where the SLEEP state is used it is recommended to use GDOx_CFGx=0x2F
- * instead. */
-#define CC1101_GDO_LNA_PD 0x1C
-
-/* RX_SYMBOL_TICK. Can be used together with RX_HARD_DATA for alternative
- * serial RX output. */
-#define CC1101_GDO_RXSYMTICK 0x1D
-
-#define CC1101_GDO_WOR_EVNT0 0x24
-#define CC1101_GDO_WOR_EVNT1 0x25
-#define CC1101_GDO_CLK32K 0x27
-#define CC1101_GDO_CHIP_RDYn 0x29
-#define CC1101_GDO_XOSC_STABLE 0x2B
-
-/* GDO0_Z_EN_N. When this output is 0, GDO0 is configured as input
- * (for serial TX data). */
-#define CC1101_GDO_GDO0_Z_EN_N 0x2D
-
-/* High impedance (3-state). */
-#define CC1101_GDO_HIZ 0x2E
-
-/* HW to 0 (HW1 achieved by setting GDOx_INV=1). Can be used to control
- * an external LNA/PA or RX/TX switch. */
-#define CC1101_GDO_HW 0x2F
-
-/* There are 3 GDO pins, but only one CLK_XOSC/n can be selected as an
- * output at any time. If CLK_XOSC/n is to be monitored on one of the
- * GDO pins, the other two GDO pins must be configured to values less
- * than 0x30. The GDO0 default value is CLK_XOSC/192. To optimize RF
- * performance, these signals should not be used while the radio is
- * in RX or TX mode. */
-#define CC1101_GDO_CLK_XOSC1 0x30
-#define CC1101_GDO_CLK_XOSC1_5 0x31
-#define CC1101_GDO_CLK_XOSC2 0x32
-#define CC1101_GDO_CLK_XOSC3 0x33
-#define CC1101_GDO_CLK_XOSC4 0x34
-#define CC1101_GDO_CLK_XOSC6 0x35
-#define CC1101_GDO_CLK_XOSC8 0x36
-#define CC1101_GDO_CLK_XOSC12 0x37
-#define CC1101_GDO_CLK_XOSC16 0x38
-#define CC1101_GDO_CLK_XOSC24 0x39
-#define CC1101_GDO_CLK_XOSC32 0x3A
-#define CC1101_GDO_CLK_XOSC48 0x3B
-#define CC1101_GDO_CLK_XOSC64 0x3C
-#define CC1101_GDO_CLK_XOSC96 0x3D
-#define CC1101_GDO_CLK_XOSC128 0x3E
-#define CC1101_GDO_CLK_XOSC192 0x3F
-
-/*
- * Others ...
- */
-
-#define CC1101_LQI_CRC_OK_BM 0x80
-#define CC1101_LQI_EST_BM 0x7F
-
-
-/************************************************************************************
- * Private Data Types
- ************************************************************************************/
-
-struct c1101_rfsettings_s {
- uint8_t FSCTRL1; /* Frequency synthesizer control. */
- uint8_t IOCFG0; /* GDO0 output pin configuration */
- uint8_t FSCTRL0; /* Frequency synthesizer control. */
- uint8_t FREQ2; /* Frequency control word, high byte. */
- uint8_t FREQ1; /* Frequency control word, middle byte. */
- uint8_t FREQ0; /* Frequency control word, low byte. */
- uint8_t MDMCFG4; /* Modem configuration. */
- uint8_t MDMCFG3; /* Modem configuration. */
- uint8_t MDMCFG2; /* Modem configuration. */
- uint8_t MDMCFG1; /* Modem configuration. */
- uint8_t MDMCFG0; /* Modem configuration. */
- uint8_t CHANNR; /* Channel number. */
- uint8_t DEVIATN; /* Modem deviation setting (when FSK modulation is enabled). */
- uint8_t FREND1; /* Front end RX configuration. */
- uint8_t FREND0; /* Front end RX configuration. */
- uint8_t MCSM0; /* Main Radio Control State Machine configuration. */
- uint8_t FOCCFG; /* Frequency Offset Compensation Configuration. */
- uint8_t BSCFG; /* Bit synchronization Configuration. */
- uint8_t AGCCTRL2; /* AGC control. */
- uint8_t AGCCTRL1; /* AGC control. */
- uint8_t AGCCTRL0; /* AGC control. */
- uint8_t FSCAL3; /* Frequency synthesizer calibration. */
- uint8_t FSCAL2; /* Frequency synthesizer calibration. */
- uint8_t FSCAL1; /* Frequency synthesizer calibration. */
- uint8_t FSCAL0; /* Frequency synthesizer calibration. */
- uint8_t FSTEST; /* Frequency synthesizer calibration control */
- uint8_t TEST2; /* Various test settings. */
- uint8_t TEST1; /* Various test settings. */
- uint8_t TEST0; /* Various test settings. */
- uint8_t FIFOTHR; /* RXFIFO and TXFIFO thresholds. */
- uint8_t IOCFG2; /* GDO2 output pin configuration */
- uint8_t PKTCTRL1; /* Packet automation control. */
- uint8_t PKTCTRL0; /* Packet automation control. */
- uint8_t ADDR; /* Device address. */
- uint8_t PKTLEN; /* Packet length. */
-};
-
-struct cc1101_dev_s {
- struct spi_dev_s * spi;
- struct c1101_rfsettings_s * settings;
-
-};
-
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/** LIS331DL Access with range check
- *
- * \param dev LIS331 DL Private Structure
- * \param subaddr LIS331 Sub Address
- * \param buf Pointer to buffer, either for read or write access
- * \param length when >0 it denotes read access, when <0 it denotes write access of -length
- * \return OK on success or errno is set.
- **/
-int cc1101_access(struct cc1101_dev_s * dev, uint8_t subaddr, uint8_t *buf, int length)
-{
- return 0;
-}
-
-
-/****************************************************************************
- * Callbacks
- ****************************************************************************/
-
-/** External line triggers this callback
- *
- * The concept todo is:
- * - GPIO provides EXTI Interrupt
- * - It should handle EXTI Interrupts in ISR, to which chipcon can
- * register a callback (and others). The ISR then foreach() calls a
- * its callback, and it is up to peripheral to find, whether the cause
- * of EXTI ISR was itself.
- **/
-void cc1101_eventcb(void)
-{
-}
-
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-struct cc1101_dev_s * cc1101_init(struct spi_dev_s * spi)
-{
- /* Powerup or wake-up, if it was previously set into some power-down state */
-
- /* Inquiry part number and version */
-
- /* Reset chip, check status bytes */
-
- /* Load it with default configuration */
-
- /* Bind to external interrupt line */
-
- return NULL;
-}
-
-
-int cc1101_deinit(struct cc1101_dev_s * dev)
-{
- /* Power down chip, possibly in some inactive state */
-
- return 0;
-}
-
-
-int cc1101_setgdo(struct cc1101_dev_s * dev, uint8_t pin, uint8_t function)
-{
- return 0;
-}
-
-
-int cc1101_setrf(struct cc1101_dev_s * dev, uint32_t frequency, int modulation)
-{
- return 0;
-}
-
-
-int cc1101_read(struct cc1101_dev_s * dev, uint8_t * data, size_t size)
-{
- return 0;
-}
-
-
-int cc1101_write(struct cc1101_dev_s * dev, const uint8_t * data, size_t size)
-{
- return 0;
-}
-
-
-int cc1101_listen(struct cc1101_dev_s * dev)
-{
- return 0;
-}
-
-
-int cc1101_send(struct cc1101_dev_s * dev)
-{
- return 0;
-}
-
-
-int cc1101_idle(struct cc1101_dev_s * dev)
-{
- return 0;
-}
-
-
-int cc1101_powerup(struct cc1101_dev_s * dev)
-{
- return 0;
-}
-
-
-int cc1101_powerdown(struct cc1101_dev_s * dev)
-{
- return 0;
-}
diff --git a/nuttx/drivers/wireless/cc1101/ISM1_868MHzGFSK100kbps.c b/nuttx/drivers/wireless/cc1101/ISM1_868MHzGFSK100kbps.c
new file mode 100644
index 000000000..5c4c58ab2
--- /dev/null
+++ b/nuttx/drivers/wireless/cc1101/ISM1_868MHzGFSK100kbps.c
@@ -0,0 +1,113 @@
+/****************************************************************************
+ * drivers/wireless/cc1101/ISM1_868MHzGFSK100kbps.c
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ * Copyright (C) 2011 Ales Verbic. All rights reserved.
+ *
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ * Ales Verbic <ales.verbic@isotel.eu>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include <nuttx/wireless/cc1101.h>
+
+/** Settings for 868 MHz, GFSK at 100kbps
+ *
+ * ISM Region 1 (Europe) only, Band 868–870 MHz
+ *
+ * Frequency ERP Duty Cycle Bandwidth Remarks
+ * 868 – 868.6 MHz +14 dBm < 1% No limits
+ * 868.7 – 869.2 MHz +14 dBm < 0.1% No limits
+ * 869.3 – 869.4 MHz +10 dBm No limits < 25 kHz Appropriate access protocol required
+ * 869.4 – 869.65 MHz +27 dBm < 10% < 25 kHz Channels may be combined to one high speed channel
+ * 869.7 -870 MHz +7 dBm No limits No limits
+ *
+ * Deviation = 46.142578
+ * Base frequency = 867.999985
+ * Carrier frequency = 867.999985
+ * Channel number = 0
+ * Carrier frequency = 867.999985
+ * Modulated = true
+ * Modulation format = GFSK
+ * Manchester enable = false
+ * Sync word qualifier mode = 30/32 sync word bits detected
+ * Preamble count = 4
+ * Channel spacing = 199.813843
+ * Carrier frequency = 867.999985
+ * Data rate = 99.9069
+ * RX filter BW = 210.937500
+ * Data format = Normal mode
+ * Length config = Fixed packet length mode. Length configured in PKTLEN register
+ * CRC enable = true
+ * Packet length = 62
+ * Device address = 00
+ * Address config = NO Address check, no broadcast
+ * CRC autoflush = true
+ * PA ramping = false
+ * TX power = 0
+ */
+const struct c1101_rfsettings_s cc1101_rfsettings_ISM1_868MHzGFSK100kbps = {
+ .FSCTRL1 = 0x08, // FSCTRL1 Frequency Synthesizer Control
+ .FSCTRL0 = 0x00, // FSCTRL0 Frequency Synthesizer Control
+
+ .FREQ2 = 0x20, // FREQ2 Frequency Control Word, High Byte
+ .FREQ1 = 0x25, // FREQ1 Frequency Control Word, Middle Byte
+ .FREQ0 = 0xED, // FREQ0 Frequency Control Word, Low Byte
+
+ .MDMCFG4 = 0x8B, // MDMCFG4 Modem Configuration
+ .MDMCFG3 = 0xE5, // MDMCFG3 Modem Configuration
+ .MDMCFG2 = 0x13, // MDMCFG2 Modem Configuration
+ .MDMCFG1 = 0x22, // MDMCFG1 Modem Configuration
+ .MDMCFG0 = 0xE5, // MDMCFG0 Modem Configuration
+
+ .DEVIATN = 0x46, // DEVIATN Modem Deviation Setting
+
+ .FOCCFG = 0x1D, // FOCCFG Frequency Offset Compensation Configuration
+
+ .BSCFG = 0x1C, // BSCFG Bit Synchronization Configuration
+
+ .AGCCTRL2= 0xC7, // AGCCTRL2 AGC Control
+ .AGCCTRL1= 0x00, // AGCCTRL1 AGC Control
+ .AGCCTRL0= 0xB2, // AGCCTRL0 AGC Control
+
+ .FREND1 = 0xB6, // FREND1 Front End RX Configuration
+ .FREND0 = 0x10, // FREND0 Front End TX Configuration
+
+ .FSCAL3 = 0xEA, // FSCAL3 Frequency Synthesizer Calibration
+ .FSCAL2 = 0x2A, // FSCAL2 Frequency Synthesizer Calibration
+ .FSCAL1 = 0x00, // FSCAL1 Frequency Synthesizer Calibration
+ .FSCAL0 = 0x1F, // FSCAL0 Frequency Synthesizer Calibration
+
+ .CHMIN = 0, // Fix at 9th channel: 869.80 MHz +- 100 kHz RF Bandwidth
+ .CHMAX = 9, // single channel
+
+ .PAMAX = 8, // 0 means power OFF, 8 represents PA[7]
+ .PA = {0x03, 0x0F, 0x1E, 0x27, 0x67, 0x50, 0x81, 0xC2}
+};
diff --git a/nuttx/drivers/wireless/cc1101/ISM2_905MHzGFSK250kbps.c b/nuttx/drivers/wireless/cc1101/ISM2_905MHzGFSK250kbps.c
new file mode 100644
index 000000000..e5655bed6
--- /dev/null
+++ b/nuttx/drivers/wireless/cc1101/ISM2_905MHzGFSK250kbps.c
@@ -0,0 +1,111 @@
+/****************************************************************************
+ * drivers/wireless/cc1101/ISM2_905MHzGFSK250kbps.c
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ * Copyright (C) 2011 Ales Verbic. All rights reserved.
+ *
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ * Ales Verbic <ales.verbic@isotel.eu>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include <nuttx/wireless/cc1101.h>
+
+/** Settings for 905 MHz, GFSK at 250kbps
+ *
+ * ISM Region 2 (America) only, Band 902–928 MHz
+ *
+ * Cordless phones 1 W
+ * Microwave ovens 750 W
+ * Industrial heaters 100 kW
+ * Military radar 1000 kW
+ *
+ * Deviation = 126.953125
+ * Base frequency = 901.999969
+ * Carrier frequency = 905.998993
+ * Channel number = 20
+ * Carrier frequency = 905.998993
+ * Modulated = true
+ * Modulation format = GFSK
+ * Manchester enable = false
+ * Sync word qualifier mode = 30/32 sync word bits detected
+ * Preamble count = 4
+ * Channel spacing = 199.951172
+ * Carrier frequency = 905.998993
+ * Data rate = 249.939
+ * RX filter BW = 541.666667
+ * Data format = Normal mode
+ * Length config = Variable packet length mode. Packet length configured by the first byte after sync word
+ * CRC enable = true
+ * Packet length = 61
+ * Device address = 0
+ * Address config = No address check
+ * CRC autoflush = false
+ * PA ramping = false
+ * TX power = 0
+ */
+const struct c1101_rfsettings_s cc1101_rfsettings_ISM2_905MHzGFSK250kbps = {
+ .FSCTRL1 = 0x0C, // FSCTRL1 Frequency Synthesizer Control
+ .FSCTRL0 = 0x00, // FSCTRL0 Frequency Synthesizer Control
+
+ .FREQ2 = 0x22, // FREQ2 Frequency Control Word, High Byte
+ .FREQ1 = 0xB1, // FREQ1 Frequency Control Word, Middle Byte
+ .FREQ0 = 0x3B, // FREQ0 Frequency Control Word, Low Byte
+
+ .MDMCFG4 = 0x2D, // MDMCFG4 Modem Configuration
+ .MDMCFG3 = 0x3B, // MDMCFG3 Modem Configuration
+ .MDMCFG2 = 0x13, // MDMCFG2 Modem Configuration
+ .MDMCFG1 = 0x22, // MDMCFG1 Modem Configuration
+ .MDMCFG0 = 0xF8, // MDMCFG0 Modem Configuration
+
+ .DEVIATN = 0x62, // DEVIATN Modem Deviation Setting
+
+ .FOCCFG = 0x1D, // FOCCFG Frequency Offset Compensation Configuration
+
+ .BSCFG = 0x1C, // BSCFG Bit Synchronization Configuration
+
+ .AGCCTRL2= 0xC7, // AGCCTRL2 AGC Control
+ .AGCCTRL1= 0x00, // AGCCTRL1 AGC Control
+ .AGCCTRL0= 0xB0, // AGCCTRL0 AGC Control
+
+ .FREND1 = 0xB6, // FREND1 Front End RX Configuration
+ .FREND0 = 0x10, // FREND0 Front End TX Configuration
+
+ .FSCAL3 = 0xEA, // FSCAL3 Frequency Synthesizer Calibration
+ .FSCAL2 = 0x2A, // FSCAL2 Frequency Synthesizer Calibration
+ .FSCAL1 = 0x00, // FSCAL1 Frequency Synthesizer Calibration
+ .FSCAL0 = 0x1F, // FSCAL0 Frequency Synthesizer Calibration
+
+ .CHMIN = 0, // VERIFY REGULATIONS!
+ .CHMAX = 0xFF,
+
+ .PAMAX = 8, // 0 means power OFF, 8 represents PA[7]
+ .PA = {0x03, 0x0E, 0x1E, 0x27, 0x39, 0x8E, 0xCD, 0xC0}
+};
diff --git a/nuttx/drivers/wireless/cc1101/cc1101.c b/nuttx/drivers/wireless/cc1101/cc1101.c
new file mode 100755
index 000000000..7bae2aebd
--- /dev/null
+++ b/nuttx/drivers/wireless/cc1101/cc1101.c
@@ -0,0 +1,773 @@
+/****************************************************************************
+ * drivers/wireless/cc1101/cc1101.c
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ *
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/** \file
+ * \author Uros Platise
+ * \brief Chipcon CC1101 Device Driver
+ *
+ * Features:
+ * - Maximum data length: 61 bytes CC1101_PACKET_MAXDATALEN
+ * - Packet length includes two additional bytes: CC1101_PACKET_MAXTOTALLEN
+ * - Requires one GDO to trigger end-of-packets in RX and TX modes.
+ * - Variable packet length with data payload between 1..61 bytes
+ * (three bytes are reserved for packet length, and RSSI and LQI
+ * appended at the end of RXFIFO after each reception)
+ * - Support for General Digital Outputs with overload protection
+ * (single XOSC pin is allowed, otherwise error is returned)
+ * - Loadable RF settings, one for ISM Region 1 (Europe) and one for
+ * ISM Region 2 (Complete America)
+ *
+ * Todo:
+ * - Extend max packet length up to 255 bytes or rather infinite < 4096 bytes
+ * - Power up/down modes
+ * - Sequencing between states or add protection for correct termination of
+ * various different state (so that CC1101 does not block in case of improper use)
+ **/
+
+#include <nuttx/config.h>
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+#include <errno.h>
+#include <stdio.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/wireless/cc1101.h>
+
+
+/****************************************************************************
+ * Declarations
+ ****************************************************************************/
+
+#define CC1101_SPIFREQ_BURST 6500000 /* Hz, no delay */
+#define CC1101_SPIFREQ_SINGLE 9000000 /* Hz, single access only - no delay */
+
+#define CC1101_MCSM0_VALUE 0x1C
+
+/****************************************************************************
+ * Chipcon CC1101 Internal Registers
+ ****************************************************************************/
+
+/* Configuration Registers */
+
+#define CC1101_IOCFG2 0x00 /* GDO2 output pin configuration */
+#define CC1101_IOCFG1 0x01 /* GDO1 output pin configuration */
+#define CC1101_IOCFG0 0x02 /* GDO0 output pin configuration */
+#define CC1101_FIFOTHR 0x03 /* RX FIFO and TX FIFO thresholds */
+#define CC1101_SYNC1 0x04 /* Sync word, high byte */
+#define CC1101_SYNC0 0x05 /* Sync word, low byte */
+#define CC1101_PKTLEN 0x06 /* Packet length */
+#define CC1101_PKTCTRL1 0x07 /* Packet automation control */
+#define CC1101_PKTCTRL0 0x08 /* Packet automation control */
+#define CC1101_ADDR 0x09 /* Device address */
+#define CC1101_CHANNR 0x0A /* Channel number */
+#define CC1101_FSCTRL1 0x0B /* Frequency synthesizer control */
+#define CC1101_FSCTRL0 0x0C /* Frequency synthesizer control */
+#define CC1101_FREQ2 0x0D /* Frequency control word, high byte */
+#define CC1101_FREQ1 0x0E /* Frequency control word, middle byte */
+#define CC1101_FREQ0 0x0F /* Frequency control word, low byte */
+#define CC1101_MDMCFG4 0x10 /* Modem configuration */
+#define CC1101_MDMCFG3 0x11 /* Modem configuration */
+#define CC1101_MDMCFG2 0x12 /* Modem configuration */
+#define CC1101_MDMCFG1 0x13 /* Modem configuration */
+#define CC1101_MDMCFG0 0x14 /* Modem configuration */
+#define CC1101_DEVIATN 0x15 /* Modem deviation setting */
+#define CC1101_MCSM2 0x16 /* Main Radio Cntrl State Machine config */
+#define CC1101_MCSM1 0x17 /* Main Radio Cntrl State Machine config */
+#define CC1101_MCSM0 0x18 /* Main Radio Cntrl State Machine config */
+#define CC1101_FOCCFG 0x19 /* Frequency Offset Compensation config */
+#define CC1101_BSCFG 0x1A /* Bit Synchronization configuration */
+#define CC1101_AGCCTRL2 0x1B /* AGC control */
+#define CC1101_AGCCTRL1 0x1C /* AGC control */
+#define CC1101_AGCCTRL0 0x1D /* AGC control */
+#define CC1101_WOREVT1 0x1E /* High byte Event 0 timeout */
+#define CC1101_WOREVT0 0x1F /* Low byte Event 0 timeout */
+#define CC1101_WORCTRL 0x20 /* Wake On Radio control */
+#define CC1101_FREND1 0x21 /* Front end RX configuration */
+#define CC1101_FREND0 0x22 /* Front end TX configuration */
+#define CC1101_FSCAL3 0x23 /* Frequency synthesizer calibration */
+#define CC1101_FSCAL2 0x24 /* Frequency synthesizer calibration */
+#define CC1101_FSCAL1 0x25 /* Frequency synthesizer calibration */
+#define CC1101_FSCAL0 0x26 /* Frequency synthesizer calibration */
+#define CC1101_RCCTRL1 0x27 /* RC oscillator configuration */
+#define CC1101_RCCTRL0 0x28 /* RC oscillator configuration */
+#define CC1101_FSTEST 0x29 /* Frequency synthesizer cal control */
+#define CC1101_PTEST 0x2A /* Production test */
+#define CC1101_AGCTEST 0x2B /* AGC test */
+#define CC1101_TEST2 0x2C /* Various test settings */
+#define CC1101_TEST1 0x2D /* Various test settings */
+#define CC1101_TEST0 0x2E /* Various test settings */
+
+/* Status registers */
+
+#define CC1101_PARTNUM (0x30 | 0xc0) /* Part number */
+#define CC1101_VERSION (0x31 | 0xc0) /* Current version number */
+#define CC1101_FREQEST (0x32 | 0xc0) /* Frequency offset estimate */
+#define CC1101_LQI (0x33 | 0xc0) /* Demodulator estimate for link quality */
+#define CC1101_RSSI (0x34 | 0xc0) /* Received signal strength indication */
+#define CC1101_MARCSTATE (0x35 | 0xc0) /* Control state machine state */
+#define CC1101_WORTIME1 (0x36 | 0xc0) /* High byte of WOR timer */
+#define CC1101_WORTIME0 (0x37 | 0xc0) /* Low byte of WOR timer */
+#define CC1101_PKTSTATUS (0x38 | 0xc0) /* Current GDOx status and packet status */
+#define CC1101_VCO_VC_DAC (0x39 | 0xc0) /* Current setting from PLL cal module */
+#define CC1101_TXBYTES (0x3A | 0xc0) /* Underflow and # of bytes in TXFIFO */
+#define CC1101_RXBYTES (0x3B | 0xc0) /* Overflow and # of bytes in RXFIFO */
+#define CC1101_RCCTRL1_STATUS (0x3C | 0xc0) /* Last RC oscilator calibration results */
+#define CC1101_RCCTRL0_STATUS (0x3D | 0xc0) /* Last RC oscilator calibration results */
+
+/* Multi byte memory locations */
+
+#define CC1101_PATABLE 0x3E
+#define CC1101_TXFIFO 0x3F
+#define CC1101_RXFIFO 0x3F
+
+/* Definitions for burst/single access to registers */
+
+#define CC1101_WRITE_BURST 0x40
+#define CC1101_READ_SINGLE 0x80
+#define CC1101_READ_BURST 0xC0
+
+/* Strobe commands */
+
+#define CC1101_SRES 0x30 /* Reset chip. */
+#define CC1101_SFSTXON 0x31 /* Enable and calibrate frequency synthesizer (if MCSM0.FS_AUTOCAL=1). */
+#define CC1101_SXOFF 0x32 /* Turn off crystal oscillator. */
+#define CC1101_SCAL 0x33 /* Calibrate frequency synthesizer and turn it off */
+#define CC1101_SRX 0x34 /* Enable RX. Perform calibration first if switching from IDLE and MCSM0.FS_AUTOCAL=1. */
+#define CC1101_STX 0x35 /* Enable TX. Perform calibration first if IDLE and MCSM0.FS_AUTOCAL=1. */
+ /* If switching from RX state and CCA is enabled then go directly to TX if channel is clear. */
+#define CC1101_SIDLE 0x36 /* Exit RX / TX, turn off frequency synthesizer and exit Wake-On-Radio mode if applicable. */
+#define CC1101_SAFC 0x37 /* Perform AFC adjustment of the frequency synthesizer */
+#define CC1101_SWOR 0x38 /* Start automatic RX polling sequence (Wake-on-Radio) */
+#define CC1101_SPWD 0x39 /* Enter power down mode when CSn goes high. */
+#define CC1101_SFRX 0x3A /* Flush the RX FIFO buffer. */
+#define CC1101_SFTX 0x3B /* Flush the TX FIFO buffer. */
+#define CC1101_SWORRST 0x3C /* Reset real time clock. */
+#define CC1101_SNOP 0x3D /* No operation. */
+
+/* Modem Control */
+
+#define CC1101_MCSM0_XOSC_FORCE_ON 0x01
+
+
+/*
+ * Chip Status Byte
+ */
+
+/* Bit fields in the chip status byte */
+
+#define CC1101_STATUS_CHIP_RDYn_BM 0x80
+#define CC1101_STATUS_STATE_BM 0x70
+#define CC1101_STATUS_FIFO_BYTES_AVAILABLE_BM 0x0F
+
+/* Chip states */
+
+#define CC1101_STATE_MASK 0x70
+#define CC1101_STATE_IDLE 0x00
+#define CC1101_STATE_RX 0x10
+#define CC1101_STATE_TX 0x20
+#define CC1101_STATE_FSTXON 0x30
+#define CC1101_STATE_CALIBRATE 0x40
+#define CC1101_STATE_SETTLING 0x50
+#define CC1101_STATE_RX_OVERFLOW 0x60
+#define CC1101_STATE_TX_UNDERFLOW 0x70
+
+/* Values of the MACRSTATE register */
+
+#define CC1101_MARCSTATE_SLEEP 0x00
+#define CC1101_MARCSTATE_IDLE 0x01
+#define CC1101_MARCSTATE_XOFF 0x02
+#define CC1101_MARCSTATE_VCOON_MC 0x03
+#define CC1101_MARCSTATE_REGON_MC 0x04
+#define CC1101_MARCSTATE_MANCAL 0x05
+#define CC1101_MARCSTATE_VCOON 0x06
+#define CC1101_MARCSTATE_REGON 0x07
+#define CC1101_MARCSTATE_STARTCAL 0x08
+#define CC1101_MARCSTATE_BWBOOST 0x09
+#define CC1101_MARCSTATE_FS_LOCK 0x0A
+#define CC1101_MARCSTATE_IFADCON 0x0B
+#define CC1101_MARCSTATE_ENDCAL 0x0C
+#define CC1101_MARCSTATE_RX 0x0D
+#define CC1101_MARCSTATE_RX_END 0x0E
+#define CC1101_MARCSTATE_RX_RST 0x0F
+#define CC1101_MARCSTATE_TXRX_SWITCH 0x10
+#define CC1101_MARCSTATE_RXFIFO_OVERFLOW 0x11
+#define CC1101_MARCSTATE_FSTXON 0x12
+#define CC1101_MARCSTATE_TX 0x13
+#define CC1101_MARCSTATE_TX_END 0x14
+#define CC1101_MARCSTATE_RXTX_SWITCH 0x15
+#define CC1101_MARCSTATE_TXFIFO_UNDERFLOW 0x16
+
+/* Part number and version */
+
+#define CC1101_PARTNUM_VALUE 0x00
+#define CC1101_VERSION_VALUE 0x04
+
+/*
+ * Others ...
+ */
+
+#define CC1101_LQI_CRC_OK_BM 0x80
+#define CC1101_LQI_EST_BM 0x7F
+
+
+/****************************************************************************
+ * Private Data Types
+ ****************************************************************************/
+
+#define FLAGS_RXONLY 1 /* Indicates receive operation only */
+#define FLAGS_XOSCENABLED 2 /* Indicates that one pin is configured as XOSC/n */
+
+struct cc1101_dev_s {
+ const struct c1101_rfsettings_s *rfsettings;
+
+ struct spi_dev_s * spi;
+ uint8_t isrpin; /* CC1101 pin used to trigger interrupts */
+ uint32_t pinset; /* GPIO of the MCU */
+ uint8_t flags;
+ uint8_t channel;
+ uint8_t power;
+};
+
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+void cc1101_access_begin(struct cc1101_dev_s * dev)
+{
+ SPI_LOCK(dev->spi, true);
+ SPI_SELECT(dev->spi, SPIDEV_WIRELESS, true);
+ SPI_SETMODE(dev->spi, SPIDEV_MODE0); /* CPOL=0, CPHA=0 */
+ SPI_SETBITS(dev->spi, 8);
+}
+
+
+void cc1101_access_end(struct cc1101_dev_s * dev)
+{
+ SPI_SELECT(dev->spi, SPIDEV_WIRELESS, false);
+ SPI_LOCK(dev->spi, false);
+}
+
+
+
+/** CC1101 Access with Range Check
+ *
+ * \param dev CC1101 Private Structure
+ * \param addr CC1101 Address
+ * \param buf Pointer to buffer, either for read or write access
+ * \param length when >0 it denotes read access, when <0 it denotes write
+ * access of -length. abs(length) greater of 1 implies burst mode,
+ * however
+ * \return OK on success or errno is set.
+ */
+int cc1101_access(struct cc1101_dev_s * dev, uint8_t addr, uint8_t *buf, int length)
+{
+ int stabyte;
+
+ /* Address cannot explicitly define READ command while length WRITE.
+ * Also access to these cells is only permitted as one byte, eventhough
+ * transfer is marked as BURST!
+ */
+
+ if ( (addr & CC1101_READ_SINGLE) && length != 1 )
+ return ERROR;
+
+ /* Prepare SPI */
+
+ cc1101_access_begin(dev);
+
+ if (length>1 || length < -1)
+ SPI_SETFREQUENCY(dev->spi, CC1101_SPIFREQ_BURST);
+ else SPI_SETFREQUENCY(dev->spi, CC1101_SPIFREQ_SINGLE);
+
+ /* Transfer */
+
+ if (length <= 0) { /* 0 length are command strobes */
+ if (length < -1)
+ addr |= CC1101_WRITE_BURST;
+
+ stabyte = SPI_SEND(dev->spi, addr);
+ if (length) {
+ SPI_SNDBLOCK(dev->spi, buf, -length);
+ }
+ }
+ else {
+ addr |= CC1101_READ_SINGLE;
+ if (length > 1)
+ addr |= CC1101_READ_BURST;
+
+ stabyte = SPI_SEND(dev->spi, addr);
+ SPI_RECVBLOCK(dev->spi, buf, length);
+ }
+
+ cc1101_access_end(dev);
+
+ return stabyte;
+}
+
+
+/** Strobes command and returns chip status byte
+ *
+ * By default commands are send as Write. To a command,
+ * CC1101_READ_SINGLE may be OR'ed to obtain the number of RX bytes
+ * pending in RX FIFO.
+ */
+inline uint8_t cc1101_strobe(struct cc1101_dev_s * dev, uint8_t command)
+{
+ uint8_t status;
+
+ cc1101_access_begin(dev);
+ SPI_SETFREQUENCY(dev->spi, CC1101_SPIFREQ_SINGLE);
+
+ status = SPI_SEND(dev->spi, command);
+
+ cc1101_access_end(dev);
+
+ return status;
+}
+
+
+int cc1101_reset(struct cc1101_dev_s * dev)
+{
+ cc1101_strobe(dev, CC1101_SRES);
+ return OK;
+}
+
+
+int cc1101_checkpart(struct cc1101_dev_s * dev)
+{
+ uint8_t partnum, version;
+
+ if (cc1101_access(dev, CC1101_PARTNUM, &partnum, 1) < 0 ||
+ cc1101_access(dev, CC1101_VERSION, &version, 1) < 0)
+ return ERROR;
+
+ if (partnum == CC1101_PARTNUM_VALUE && version == CC1101_VERSION_VALUE)
+ return OK;
+
+ return ERROR;
+}
+
+
+void cc1101_dumpregs(struct cc1101_dev_s * dev, uint8_t addr, uint8_t length)
+{
+ uint8_t buf[0x30], i;
+
+ cc1101_access(dev, addr, buf, length);
+
+ printf("CC1101[%2x]: ", addr);
+ for (i=0; i<length; i++) printf(" %2x,", buf[i]);
+ printf("\n");
+}
+
+
+void cc1101_setpacketctrl(struct cc1101_dev_s * dev)
+{
+ uint8_t values[3];
+
+ values[0] = 0; /* Rx FIFO threshold = 32, Tx FIFO threshold = 33 */
+ cc1101_access(dev, CC1101_FIFOTHR, values, -1);
+
+ /* Packet length
+ * Limit it to 61 bytes in total: pktlen, data[61], rssi, lqi
+ */
+
+ values[0] = CC1101_PACKET_MAXDATALEN;
+ cc1101_access(dev, CC1101_PKTLEN, values, -1);
+
+ /* Packet Control */
+
+ values[0] = 0x04; /* Append status: RSSI and LQI at the end of received packet */
+ /* TODO: CRC Auto Flash bit 0x08 ??? */
+ values[1] = 0x05; /* CRC in Rx and Tx Enabled: Variable Packet mode, defined by first byte */
+ /* TODO: Enable data whitening ... */
+ cc1101_access(dev, CC1101_PKTCTRL1, values, -2);
+
+ /* Main Radio Control State Machine */
+
+ values[0] = 0x07; /* No time-out */
+ values[1] = 0x00; /* Clear channel if RSSI < thr && !receiving;
+ * TX -> RX, RX -> RX: 0x3F */
+ values[2] = CC1101_MCSM0_VALUE; /* Calibrate on IDLE -> RX/TX, OSC Timeout = ~500 us
+ TODO: has XOSC_FORCE_ON */
+ cc1101_access(dev, CC1101_MCSM2, values, -3);
+
+ /* Wake-On Radio Control */
+
+ // Not used yet.
+
+ // WOREVT1:WOREVT0 - 16-bit timeout register
+}
+
+
+/****************************************************************************
+ * Callbacks
+ ****************************************************************************/
+
+volatile int cc1101_interrupt = 0;
+
+/** External line triggers this callback
+ *
+ * The concept todo is:
+ * - GPIO provides EXTI Interrupt
+ * - It should handle EXTI Interrupts in ISR, to which chipcon can
+ * register a callback (and others). The ISR then foreach() calls a
+ * its callback, and it is up to peripheral to find, whether the cause
+ * of EXTI ISR was itself.
+ **/
+void cc1101_eventcb(void)
+{
+ cc1101_interrupt++;
+}
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+struct cc1101_dev_s * cc1101_init(struct spi_dev_s * spi, uint8_t isrpin,
+ uint32_t pinset, const struct c1101_rfsettings_s * rfsettings)
+{
+ struct cc1101_dev_s * dev;
+
+ ASSERT(spi);
+
+ if ( (dev = kmalloc( sizeof(struct cc1101_dev_s) )) == NULL) {
+ errno = ENOMEM;
+ return NULL;
+ }
+
+ dev->rfsettings = rfsettings;
+ dev->spi = spi;
+ dev->isrpin = isrpin;
+ dev->pinset = pinset;
+ dev->flags = 0;
+ dev->channel = rfsettings->CHMIN;
+ dev->power = rfsettings->PAMAX;
+
+ /* Reset chip, check status bytes */
+
+ if ( cc1101_reset(dev) < 0 ) {
+ kfree(dev);
+ errno = EFAULT;
+ return NULL;
+ }
+
+ /* Check part compatibility */
+
+ if ( cc1101_checkpart(dev) < 0 ) {
+ kfree(dev);
+ errno = ENODEV;
+ return NULL;
+ }
+
+ /* Configure CC1101:
+ * - disable GDOx for best performance
+ * - load RF
+ * - and packet control
+ */
+
+ cc1101_setgdo(dev, CC1101_PIN_GDO0, CC1101_GDO_HIZ);
+ cc1101_setgdo(dev, CC1101_PIN_GDO1, CC1101_GDO_HIZ);
+ cc1101_setgdo(dev, CC1101_PIN_GDO2, CC1101_GDO_HIZ);
+ cc1101_setrf(dev, rfsettings);
+ cc1101_setpacketctrl(dev);
+
+ /* Set the ISR to be triggerred on falling edge of the:
+ *
+ * 6 (0x06) Asserts when sync word has been sent / received, and
+ * de-asserts at the end of the packet. In RX, the pin will de-assert
+ * when the optional address check fails or the RX FIFO overflows.
+ * In TX the pin will de-assert if the TX FIFO underflows.
+ */
+
+ cc1101_setgdo(dev, dev->isrpin, CC1101_GDO_SYNC);
+
+ /* Bind to external interrupt line */
+
+ // depends on STM32: TODO: Make that config within pinset and
+ // provide general gpio interface
+ //stm32_gpiosetevent(pinset, false, true, true, cc1101_eventcb);
+
+ return dev;
+}
+
+
+int cc1101_deinit(struct cc1101_dev_s * dev)
+{
+ ASSERT(dev);
+
+ /* Release interrupt */
+ //stm32_gpiosetevent(pinset, false, false, false, NULL);
+
+ /* Power down chip */
+ cc1101_powerdown(dev);
+
+ /* Release external interrupt line */
+ kfree(dev);
+
+ return 0;
+}
+
+
+int cc1101_powerup(struct cc1101_dev_s * dev)
+{
+ ASSERT(dev);
+ return 0;
+}
+
+
+int cc1101_powerdown(struct cc1101_dev_s * dev)
+{
+ ASSERT(dev);
+ return 0;
+}
+
+
+int cc1101_setgdo(struct cc1101_dev_s * dev, uint8_t pin, uint8_t function)
+{
+ ASSERT(dev);
+ ASSERT(pin <= CC1101_IOCFG0);
+
+ if (function >= CC1101_GDO_CLK_XOSC1) {
+
+ /* Only one pin can be enabled at a time as XOSC/n */
+
+ if (dev->flags & FLAGS_XOSCENABLED) return -EPERM;
+
+ /* Force XOSC to stay active even in sleep mode */
+
+ int value = CC1101_MCSM0_VALUE | CC1101_MCSM0_XOSC_FORCE_ON;
+ cc1101_access(dev, CC1101_MCSM0, &value, -1);
+
+ dev->flags |= FLAGS_XOSCENABLED;
+ }
+ else if (dev->flags & FLAGS_XOSCENABLED) {
+
+ /* Disable XOSC in sleep mode */
+
+ int value = CC1101_MCSM0_VALUE;
+ cc1101_access(dev, CC1101_MCSM0, &value, -1);
+
+ dev->flags &= ~FLAGS_XOSCENABLED;
+ }
+
+ return cc1101_access(dev, pin, &function, -1);
+}
+
+
+int cc1101_setrf(struct cc1101_dev_s * dev, const struct c1101_rfsettings_s *settings)
+{
+ ASSERT(dev);
+ ASSERT(settings);
+
+ if (cc1101_access(dev, CC1101_FSCTRL1, &settings->FSCTRL1, -11) < 0) return ERROR;
+ if (cc1101_access(dev, CC1101_FOCCFG, &settings->FOCCFG, -5) < 0) return ERROR;
+ if (cc1101_access(dev, CC1101_FREND1, &settings->FREND1, -6) < 0) return ERROR;
+
+ /* Load Power Table */
+
+ if (cc1101_access(dev, CC1101_PATABLE, settings->PA, -8) < 0) return ERROR;
+
+ /* If channel is out of valid range, mark that. Limit power.
+ * We are not allowed to send any data, but are allowed to listen
+ * and receive.
+ */
+
+ cc1101_setchannel(dev, dev->channel);
+ cc1101_setpower(dev, dev->power);
+
+ return OK;
+}
+
+
+int cc1101_setchannel(struct cc1101_dev_s * dev, uint8_t channel)
+{
+ ASSERT(dev);
+
+ /* Store localy in further checks */
+
+ dev->channel = channel;
+
+ /* If channel is out of valid, we are allowed to listen and receive only */
+
+ if (channel < dev->rfsettings->CHMIN || channel > dev->rfsettings->CHMAX)
+ dev->flags |= FLAGS_RXONLY;
+ else dev->flags &= ~FLAGS_RXONLY;
+
+ cc1101_access(dev, CC1101_CHANNR, &dev->channel, -1);
+
+ return dev->flags & FLAGS_RXONLY;
+}
+
+
+uint8_t cc1101_setpower(struct cc1101_dev_s * dev, uint8_t power)
+{
+ ASSERT(dev);
+
+ if (power > dev->rfsettings->PAMAX)
+ power = dev->rfsettings->PAMAX;
+
+ dev->power = power;
+
+ if (power == 0) {
+ dev->flags |= FLAGS_RXONLY;
+ return 0;
+ }
+ else dev->flags &= ~FLAGS_RXONLY;
+
+ /* Add remaining part from RF table (to get rid of readback) */
+
+ power--;
+ power |= dev->rfsettings->FREND0;
+
+ /* On error, report that as zero power */
+
+ if (cc1101_access(dev, CC1101_FREND0, &power, -1) < 0)
+ dev->power = 0;
+
+ return dev->power;
+}
+
+
+int cc1101_calcRSSIdBm(int rssi)
+{
+ if (rssi >= 128) rssi -= 256;
+ return (rssi >> 1) - 74;
+}
+
+
+int cc1101_receive(struct cc1101_dev_s * dev)
+{
+ ASSERT(dev);
+
+ /* \todo Wait for IDLE before going into another state? */
+
+ cc1101_interrupt = 0;
+
+ cc1101_strobe(dev, CC1101_SRX | CC1101_READ_SINGLE);
+
+ return 0;
+}
+
+
+int cc1101_read(struct cc1101_dev_s * dev, uint8_t * buf, size_t size)
+{
+ ASSERT(dev);
+
+ if (buf==NULL) {
+ if (size==0) return 64;
+ // else received packet size
+ return 0;
+ }
+
+ if (cc1101_interrupt == 0) return 0;
+
+ int status = cc1101_strobe(dev, CC1101_SNOP | CC1101_READ_SINGLE);
+
+ if (status & CC1101_STATUS_FIFO_BYTES_AVAILABLE_BM &&
+ (status & CC1101_STATE_MASK) == CC1101_STATE_IDLE) {
+
+ uint8_t nbytes;
+
+ cc1101_access(dev, CC1101_RXFIFO, &nbytes, 1);
+
+ nbytes += 2; /* RSSI and LQI */
+
+ cc1101_access(dev, CC1101_RXFIFO, buf, (nbytes > size) ? size : nbytes);
+
+ /* Flush remaining bytes, if there is no room to receive
+ * or if there is a BAD CRC
+ */
+
+ if (nbytes > size || (nbytes <= size && !(buf[nbytes-1]&0x80)) ) {
+ printf("Flushing RX FIFO\n");
+ cc1101_strobe(dev, CC1101_SFRX);
+ }
+
+ return nbytes;
+ }
+
+ return 0;
+}
+
+
+int cc1101_write(struct cc1101_dev_s * dev, const uint8_t * buf, size_t size)
+{
+ uint8_t packetlen;
+
+ ASSERT(dev);
+ ASSERT(buf);
+
+ if (dev->flags & FLAGS_RXONLY) return -EPERM;
+
+ /* Present limit */
+ if (size > CC1101_PACKET_MAXDATALEN)
+ packetlen = CC1101_PACKET_MAXDATALEN;
+ else packetlen = size;
+
+ cc1101_access(dev, CC1101_TXFIFO, &packetlen, -1);
+ cc1101_access(dev, CC1101_TXFIFO, buf, -size);
+
+ return 0;
+}
+
+
+int cc1101_send(struct cc1101_dev_s * dev)
+{
+ ASSERT(dev);
+
+ if (dev->flags & FLAGS_RXONLY) return -EPERM;
+
+ cc1101_interrupt = 0;
+
+ cc1101_strobe(dev, CC1101_STX);
+
+ /* wait until send, going to IDLE */
+
+ while( cc1101_interrupt == 0 );
+
+ return 0;
+}
+
+
+int cc1101_idle(struct cc1101_dev_s * dev)
+{
+ ASSERT(dev);
+ cc1101_strobe(dev, CC1101_SIDLE);
+ return 0;
+}