summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-03-25 14:51:25 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-03-25 14:51:25 +0000
commitdac9280da1557443ff9eff12105479ea43c241f7 (patch)
tree4738f897312e97d5719542dfc88b4609da4b1ab6 /nuttx/arch
parentbf30dc09b0c7d49d556196f4d35b5e0fef2c7e7e (diff)
downloadpx4-nuttx-dac9280da1557443ff9eff12105479ea43c241f7.tar.gz
px4-nuttx-dac9280da1557443ff9eff12105479ea43c241f7.tar.bz2
px4-nuttx-dac9280da1557443ff9eff12105479ea43c241f7.zip
Add support for the poweroff on calypso phones
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4520 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/calypso/Make.defs4
-rw-r--r--nuttx/arch/arm/src/calypso/calypso_power.c18
-rw-r--r--nuttx/arch/arm/src/calypso/calypso_spi.c141
3 files changed, 161 insertions, 2 deletions
diff --git a/nuttx/arch/arm/src/calypso/Make.defs b/nuttx/arch/arm/src/calypso/Make.defs
index cebf503b7..cfd036cdf 100644
--- a/nuttx/arch/arm/src/calypso/Make.defs
+++ b/nuttx/arch/arm/src/calypso/Make.defs
@@ -46,8 +46,8 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
up_interruptcontext.c up_prefetchabort.c up_releasepending.c \
up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \
up_sigdeliver.c up_syscall.c up_unblocktask.c \
- up_undefinedinsn.c up_usestack.c
+ up_undefinedinsn.c up_usestack.c calypso_power.c
CHIP_ASRCS = calypso_lowputc.S
CHIP_CSRCS = calypso_irq.c calypso_timer.c calypso_heap.c \
- calypso_serial.c clock.c
+ calypso_serial.c calypso_spi.c clock.c
diff --git a/nuttx/arch/arm/src/calypso/calypso_power.c b/nuttx/arch/arm/src/calypso/calypso_power.c
new file mode 100644
index 000000000..f85d6890e
--- /dev/null
+++ b/nuttx/arch/arm/src/calypso/calypso_power.c
@@ -0,0 +1,18 @@
+#include <stdio.h>
+#include <nuttx/spi.h>
+
+int board_power_off(void)
+{
+ uint16_t tx;
+ struct spi_dev_s *spi = up_spiinitialize(0);
+
+ SPI_SETBITS(spi, 16);
+
+ tx = (1 << 6) | (1 << 1);
+ SPI_SNDBLOCK(spi, &tx, 1);
+
+ tx = (1 << 6) | (30 << 1);
+ SPI_SNDBLOCK(spi, &tx, 1);
+
+ return 0;
+}
diff --git a/nuttx/arch/arm/src/calypso/calypso_spi.c b/nuttx/arch/arm/src/calypso/calypso_spi.c
new file mode 100644
index 000000000..cc20f2072
--- /dev/null
+++ b/nuttx/arch/arm/src/calypso/calypso_spi.c
@@ -0,0 +1,141 @@
+/****************************************************************************
+ * calypso_spi.c
+ * SPI driver for TI Calypso
+ *
+ * Copyright (C) 2011 Stefan Richter <ichgeh@l--putt.de>
+ *
+ * All rights reserved.
+ *
+ * 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/config.h>
+#include <nuttx/spi.h>
+
+#warning "MOST OF SPI API IS INCOMPLETE! (Wrapper around Osmocom driver)"
+extern void spi_init(void);
+extern int spi_xfer(uint8_t dev_idx, uint8_t bitlen, const void *dout, void *din);
+
+#ifndef CONFIG_SPI_EXCHANGE
+#error "Calypso HW only supports exchange. Enable CONFIG_SPI_EXCHANGE!"
+#endif
+
+struct calypso_spidev_s
+{
+ struct spi_dev_s spidev; /* External driver interface */
+ int nbits; /* Number of transfered bits */
+
+#ifndef CONFIG_SPI_OWNBUS
+ sem_t exclsem; /* Mutual exclusion of devices */
+#endif
+};
+
+/* STUBS! */
+#ifndef CONFIG_SPI_OWNBUS
+static int spi_lock(FAR struct spi_dev_s *dev, bool lock);
+#endif
+
+static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
+ bool selected)
+{
+}
+
+static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
+{
+ return frequency;
+}
+
+static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
+{
+}
+
+/* Osmocom wrapper */
+static void spi_setbits(FAR struct spi_dev_s *dev, int nbits)
+{
+ ((FAR struct calypso_spidev_s *)dev)->nbits = nbits;
+}
+
+static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
+ FAR void *rxbuffer, size_t nwords)
+{
+ FAR struct calypso_spidev_s *priv = (FAR struct calypso_spidev_s *)dev;
+ size_t i;
+
+ for(i=0; i<nwords; i++)
+ spi_xfer(0, priv->nbits, txbuffer+i, rxbuffer+i);
+}
+
+static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd)
+{
+ uint16_t buf = wd;
+ spi_exchange(dev, &buf, &buf, 1);
+ return buf;
+}
+
+static const struct spi_ops_s g_spiops =
+{
+#ifndef CONFIG_SPI_OWNBUS
+ .lock = spi_lock,
+#endif
+ .select = spi_select,
+ .setfrequency = spi_setfrequency,
+ .setmode = spi_setmode,
+ .setbits = spi_setbits,
+ .status = 0,
+#ifdef CONFIG_SPI_CMDDATA
+ .cmddata = ,
+#endif
+ .send = spi_send,
+#ifdef CONFIG_SPI_EXCHANGE
+ .exchange = spi_exchange,
+#else
+ .sndblock = spi_sndblock,
+ .recvblock = spi_recvblock,
+#endif
+ .registercallback = 0,
+};
+
+static struct calypso_spidev_s g_spidev =
+{
+ .spidev = { &g_spiops },
+ .nbits = 0,
+};
+
+FAR struct spi_dev_s *up_spiinitialize(int port)
+{
+ switch(port) {
+ case 0: /* SPI master device */
+ spi_init();
+ return (FAR struct spi_dev_s *)&g_spidev;
+ case 1: /* uWire device */
+ return NULL;
+ default:
+ return NULL;
+ }
+}