summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-06-18 11:20:57 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-06-18 11:20:57 -0600
commit9143d0ffcf1bb691480c6657651fc06c7b027a5c (patch)
treeefdfd008bdd3b736ea39bb9f4b9aee5df89b6148
parentd455832c02729971e4990fd422958ad2623d4dfe (diff)
downloadpx4-nuttx-9143d0ffcf1bb691480c6657651fc06c7b027a5c.tar.gz
px4-nuttx-9143d0ffcf1bb691480c6657651fc06c7b027a5c.tar.bz2
px4-nuttx-9143d0ffcf1bb691480c6657651fc06c7b027a5c.zip
Freescale KL25Z support from Alan Carvalho de Assis
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_memorymap.h2
-rw-r--r--nuttx/arch/arm/src/kl/chip/kl_tsi.h154
-rw-r--r--nuttx/configs/freedom-kl25z/include/board.h14
-rw-r--r--nuttx/configs/freedom-kl25z/src/Makefile6
-rw-r--r--nuttx/configs/freedom-kl25z/src/kl_boardinitialize.c26
-rw-r--r--nuttx/configs/freedom-kl25z/src/kl_nsh.c92
-rw-r--r--nuttx/configs/freedom-kl25z/src/kl_tsi.c261
8 files changed, 557 insertions, 3 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index fa28b0eff..8cd045ec6 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -5000,4 +5000,7 @@
(2013-6-18)
* arch/arm/src/sam34/sam_spi.c: Fix SPI mode setting. In the SAM3/4
family, the clock phase control (CPHA) is inverted (NPHA) (2013-6-18).
-
+ * arch/arm/src/kl/chip/kl_tsi.h: Freescale KL25Z TSI register
+ definitions from Alan Carvalho de Assis (2013-6-18).
+ * configs/freedom-kl25z/src/kl_tsi.c: Example TSI driver for the
+ Freedom KL25Z board from Alan Carvalho de Assis (2013-6-18).
diff --git a/nuttx/arch/arm/src/kl/chip/kl_memorymap.h b/nuttx/arch/arm/src/kl/chip/kl_memorymap.h
index 60e4542c7..351c87e54 100644
--- a/nuttx/arch/arm/src/kl/chip/kl_memorymap.h
+++ b/nuttx/arch/arm/src/kl/chip/kl_memorymap.h
@@ -87,7 +87,7 @@
# define KL_RTC_BASE 0x4003d000 /* Real time clock */
# define KL_DAC0_BASE 0x4003f000 /* Digital-to-analog convert (DAC) 0 */
# define KL_LPTMR_BASE 0x40040000 /* Low power timer */
-# define KL_TSI0_BASE 0x40045000 /* Touch sense interface */
+# define KL_TSI_BASE 0x40045000 /* Touch sense interface */
# define KL_SIMLP_BASE 0x40047000 /* SIM low-power logic */
# define KL_SIM_BASE 0x40048000 /* System integration module (SIM) */
# define KL_PORT_BASE(n) (0x40049000 + ((n) << 12))
diff --git a/nuttx/arch/arm/src/kl/chip/kl_tsi.h b/nuttx/arch/arm/src/kl/chip/kl_tsi.h
new file mode 100644
index 000000000..8e0d87e90
--- /dev/null
+++ b/nuttx/arch/arm/src/kl/chip/kl_tsi.h
@@ -0,0 +1,154 @@
+/************************************************************************************
+ * arch/arm/src/kl/chip/kl_tsi.h
+ *
+ * Copyright (C) 2013 Alan Carvalho de Assis
+ * Author: Alan Carvalho de Assis <acassis@gmail.com>
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_KL_CHIP_KL_TSI_H
+#define __ARCH_ARM_SRC_KL_CHIP_KL_TSI_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define KL_TSI_GENCS_OFFSET 0x0000 /* General Control and Status Register */
+#define KL_TSI_DATA_OFFSET 0x0004 /* SCAN control register */
+#define KL_TSI_TSHD_OFFSET 0x0008 /* Pin enable register */
+
+/* Register Addresses ***************************************************************/
+
+#define KL_TSI_GENCS (KL_TSI_BASE+KL_TSI_GENCS_OFFSET)
+#define KL_TSI_DATA (KL_TSI_BASE+KL_TSI_DATA_OFFSET)
+#define KL_TSI_TSHD (KL_TSI_BASE+KL_TSI_TSHD_OFFSET)
+
+/* Register Bit Definitions *********************************************************/
+
+/* General Control and Status Register */
+ /* Bit 0: Reserved */
+#define TSI_GENCS_CURSW (1 << 1) /* Bit 1: Current sources for oscillators swapped */
+#define TSI_GENCS_EOSF (1 << 2) /* Bit 2: End of scan flag */
+#define TSI_GENCS_SCNIP (1 << 3) /* Bit 3: Scan in progress status */
+#define TSI_GENCS_STM (1 << 4) /* Bit 4: Scan trigger mode */
+#define TSI_GENCS_STPE (1 << 5) /* Bit 5: TSI STOP enable */
+#define TSI_GENCS_TSIIEN (1 << 6) /* Bit 6: TSI module interrupt enable */
+#define TSI_GENCS_TSIEN (1 << 7) /* Bit 7: TSI module enable */
+#define TSI_GENCS_NSCN_SHIFT (8) /* Bits 8-12: Electrode oscillator count used in a scan */
+#define TSI_GENCS_NSCN_MASK (31 << TSI_GENCS_NSCN_SHIFT)
+# define TSI_GENCS_NSCN_TIMES(n) (((n)-1) << TSI_GENCS_NSCN_SHIFT) /* n times per electrode,n=1..32 */
+#define TSI_GENCS_PS_SHIFT (13) /* Bits 13-15: Prescaler value */
+#define TSI_GENCS_PS_MASK (7 << TSI_GENCS_PS_SHIFT)
+# define TSI_GENCS_PS_DIV1 (0 << TSI_GENCS_PS_SHIFT) /* Electrode oscillator / 1 */
+# define TSI_GENCS_PS_DIV2 (1 << TSI_GENCS_PS_SHIFT) /* Electrode oscillator / 2 */
+# define TSI_GENCS_PS_DIV4 (2 << TSI_GENCS_PS_SHIFT) /* Electrode oscillator / 4 */
+# define TSI_GENCS_PS_DIV8 (3 << TSI_GENCS_PS_SHIFT) /* Electrode oscillator / 8 */
+# define TSI_GENCS_PS_DIV16 (4 << TSI_GENCS_PS_SHIFT) /* Electrode oscillator / 16 */
+# define TSI_GENCS_PS_DIV32 (5 << TSI_GENCS_PS_SHIFT) /* Electrode oscillator / 32 */
+# define TSI_GENCS_PS_DIV64 (6 << TSI_GENCS_PS_SHIFT) /* Electrode oscillator / 64 */
+# define TSI_GENCS_PS_DIV128 (7 << TSI_GENCS_PS_SHIFT) /* Electrode oscillator / 128 */
+#define TSI_GENCS_EXTCHRG_SHIFT (16) /* Bits 16-18: Electrode Osc charge/discharge value */
+#define TSI_GENCS_EXTCHRG_MASK (7 << TSI_GENCS_EXTCHRG_SHIFT)
+# define TSI_GENCS_EXTCHRG_500NA (0 << TSI_GENCS_EXTCHRG_SHIFT)
+# define TSI_GENCS_EXTCHRG_1UA (1 << TSI_GENCS_EXTCHRG_SHIFT)
+# define TSI_GENCS_EXTCHRG_2UA (2 << TSI_GENCS_EXTCHRG_SHIFT)
+# define TSI_GENCS_EXTCHRG_4UA (3 << TSI_GENCS_EXTCHRG_SHIFT)
+# define TSI_GENCS_EXTCHRG_8UA (4 << TSI_GENCS_EXTCHRG_SHIFT)
+# define TSI_GENCS_EXTCHRG_16UA (5 << TSI_GENCS_EXTCHRG_SHIFT)
+# define TSI_GENCS_EXTCHRG_32UA (6 << TSI_GENCS_EXTCHRG_SHIFT)
+# define TSI_GENCS_EXTCHRG_64A (7 << TSI_GENCS_EXTCHRG_SHIFT)
+#define TSI_GENCS_DVOLT_SHIFT (19) /* Bits 19-20: Oscilattor voltage rails */
+#define TSI_GENCS_DVOLT_MASK (3 << TSI_GENCS_DVOLT_SHIFT)
+# define TSI_GENCS_DVOLT_1p03V (0 << TSI_GENCS_DVOLT_SHIFT)
+# define TSI_GENCS_DVOLT_0p73V (1 << TSI_GENCS_DVOLT_SHIFT)
+# define TSI_GENCS_DVOLT_0p43V (2 << TSI_GENCS_DVOLT_SHIFT)
+# define TSI_GENCS_DVOLT_0p29V (3 << TSI_GENCS_DVOLT_SHIFT)
+#define TSI_GENCS_REFCHRG_SHIFT (21) /* Bits 21-23: Reference Osc charge/discharge value */
+#define TSI_GENCS_REFCHRG_MASK (7 << TSI_GENCS_REFCHRG_SHIFT)
+# define TSI_GENCS_REFCHRG_500NA (0 << TSI_GENCS_REFCHRG_SHIFT)
+# define TSI_GENCS_REFCHRG_1UA (1 << TSI_GENCS_REFCHRG_SHIFT)
+# define TSI_GENCS_REFCHRG_2UA (2 << TSI_GENCS_REFCHRG_SHIFT)
+# define TSI_GENCS_REFCHRG_4UA (3 << TSI_GENCS_REFCHRG_SHIFT)
+# define TSI_GENCS_REFCHRG_8UA (4 << TSI_GENCS_REFCHRG_SHIFT)
+# define TSI_GENCS_REFCHRG_16UA (5 << TSI_GENCS_REFCHRG_SHIFT)
+# define TSI_GENCS_REFCHRG_32UA (6 << TSI_GENCS_REFCHRG_SHIFT)
+# define TSI_GENCS_REFCHRG_64UA (7 << TSI_GENCS_REFCHRG_SHIFT)
+#define TSI_GENCS_MODE_SHIFT (24) /* Bits 24-27: Analog mode setup and status bits */
+#define TSI_GENCS_MODE_MASK (15 << TSI_GENCS_MODE_SHIFT)
+# define TSI_GENCS_MODE_CAPSENSING (0 << TSI_GENCS_MODE_SHIFT)
+# define TSI_GENCS_MODE_SGTSHD_NOFREQ (4 << TSI_GENCS_MODE_SHIFT)
+# define TSI_GENCS_MODE_SGTSHD_FRQLIM (8 << TSI_GENCS_MODE_SHIFT)
+# define TSI_GENCS_MODE_AUTODETECT (12 << TSI_GENCS_MODE_SHIFT)
+#define TSI_GENCS_ESOR (1 << 28) /* Bit 28: End/Out-of-range interrupt selection */
+ /* Bits 29-30: Reserved */
+#define TSI_GENCS_OUTRFG (1 << 31) /* Bit 31: Out of range flag */
+
+/* SCAN control register */
+
+#define TSI_DATA_TSICNT_SHIFT (0) /* Bits 0-15: TSI Conversion counter value */
+#define TSI_DATA_TSICNT_MASK (0xffff << TSI_DATA_TSICNT_SHIFT)
+ /* Bits 16-21: Reserved */
+#define TSI_DATA_SWTS (1 << 22) /* Bit 22: Software trigger start */
+#define TSI_DATA_DMAEN (1 << 23) /* Bit 23: DMA Transfer enabled */
+ /* Bits 24-27: Reserved */
+#define TSI_DATA_TSICH_SHIFT (28) /* Bits 28-31: Current channel to be measured */
+#define TSI_DATA_TSICH_MASK (15 << TSI_DATA_TSICH_SHIFT)
+# define TSI_DATA_TSICH(n) (n << TSI_DATA_TSICH_SHIFT) /* Channel to measure, n=0..15 */
+
+/* Channel n threshold register */
+
+#define TSI_THRESHLD_HTHH_SHIFT (0) /* Bits 0-15: High threshold value */
+#define TSI_THRESHLD_HTHH_MASK (0xffff << TSI_THRESHLD_HTHH_SHIFT)
+#define TSI_THRESHLD_LTHH_SHIFT (16) /* Bits 16-31: Low threshold value */
+#define TSI_THRESHLD_LTHH_MASK (0xffff << TSI_THRESHLD_LTHH_SHIFT)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_KL_CHIP_KL_TSI_H */
diff --git a/nuttx/configs/freedom-kl25z/include/board.h b/nuttx/configs/freedom-kl25z/include/board.h
index cb42980da..08e9e0afe 100644
--- a/nuttx/configs/freedom-kl25z/include/board.h
+++ b/nuttx/configs/freedom-kl25z/include/board.h
@@ -312,6 +312,20 @@ extern "C" {
void kl_boardinitialize(void);
+/************************************************************************************
+ * Name: kl_tsi_initialize
+ *
+ * Description:
+ * Initialize the TSI hardware and interface for the sliders on board the Freedom
+ * KL25Z board. Register a character driver at /dev/tsi that may be used to read
+ * from each sensor.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_KL_TSI
+void kl_tsi_initialize(void);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/configs/freedom-kl25z/src/Makefile b/nuttx/configs/freedom-kl25z/src/Makefile
index 30333c4cc..68db441bc 100644
--- a/nuttx/configs/freedom-kl25z/src/Makefile
+++ b/nuttx/configs/freedom-kl25z/src/Makefile
@@ -42,6 +42,10 @@ AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = kl_boardinitialize.c
+ifeq ($(CONFIG_KL_TSI),y)
+CSRCS += kl_tsi.c
+endif
+
ifeq ($(CONFIG_HAVE_CXX),y)
CSRCS += kl_cxxinitialize.c
endif
@@ -66,7 +70,7 @@ ifeq ($(CONFIG_WATCHDOG),y)
CSRCS += kl_watchdog.c
endif
-ifeq ($(CONFIG_NSH_ARCHINIT),y)
+ifeq ($(CONFIG_NSH_LIBRARY),y)
CSRCS += kl_nsh.c
endif
diff --git a/nuttx/configs/freedom-kl25z/src/kl_boardinitialize.c b/nuttx/configs/freedom-kl25z/src/kl_boardinitialize.c
index 562302237..eff2873b1 100644
--- a/nuttx/configs/freedom-kl25z/src/kl_boardinitialize.c
+++ b/nuttx/configs/freedom-kl25z/src/kl_boardinitialize.c
@@ -100,3 +100,29 @@ void kl_boardinitialize(void)
kl_ledinit();
#endif
}
+/****************************************************************************
+ * Name: board_initialize
+ *
+ * Description:
+ * If CONFIG_BOARD_INITIALIZE is selected, then an additional
+ * initialization call will be performed in the boot-up sequence to a
+ * function called board_initialize(). board_initialize() will be
+ * called immediately after up_intitialize() is called and just before the
+ * initial application is started. This additional initialization phase
+ * may be used, for example, to initialize board-specific device drivers.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_BOARD_INITIALIZE
+void board_initialize(void)
+{
+ /* Perform NSH initialization here instead of from the NSH. This
+ * alternative NSH initialization is necessary when NSH is ran in user-space
+ * but the initialization function must run in kernel space.
+ */
+
+#if defined(CONFIG_NSH_LIBRARY) && !defined(CONFIG_NSH_ARCHINIT)
+ (void)nsh_archinitialize();
+#endif
+}
+#endif
diff --git a/nuttx/configs/freedom-kl25z/src/kl_nsh.c b/nuttx/configs/freedom-kl25z/src/kl_nsh.c
new file mode 100644
index 000000000..3b9187466
--- /dev/null
+++ b/nuttx/configs/freedom-kl25z/src/kl_nsh.c
@@ -0,0 +1,92 @@
+/****************************************************************************
+ * config/stm32f4discovery/src/kl_nsh.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdio.h>
+
+#ifdef CONFIG_NSH_LIBRARY
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# if defined(CONFIG_DEBUG) || !defined(CONFIG_NSH_ARCHINIT)
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# if defined(CONFIG_DEBUG) || !defined(CONFIG_NSH_ARCHINIT)
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ * CONFIG_NSH_ARCHINIT=y :
+ * Called from the NSH library
+ *
+ * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
+ * CONFIG_NSH_ARCHINIT=n :
+ * Called from board_initialize().
+ *
+ ****************************************************************************/
+
+int nsh_archinitialize(void)
+{
+ return OK;
+}
+
+#endif /* CONFIG_NSH_LIBRARY */
diff --git a/nuttx/configs/freedom-kl25z/src/kl_tsi.c b/nuttx/configs/freedom-kl25z/src/kl_tsi.c
new file mode 100644
index 000000000..18afb4580
--- /dev/null
+++ b/nuttx/configs/freedom-kl25z/src/kl_tsi.c
@@ -0,0 +1,261 @@
+/****************************************************************************
+ * configs/freedom-kl25z/src/kl_tsi.c
+ *
+ * Copyright (C) 2013 Alan Carvalho de Assis
+ * Author: Alan Carvalho de Assis <acassis@gmail.com>
+ * with adaptions from Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Reference: https://community.freescale.com/community/
+ * the-embedded-beat/blog/2012/10/15/
+ * using-the-touch-interface-on-the-freescale-freedom-development-platform
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/fs/fs.h>
+
+#include "up_arch.h"
+#include "kl_gpio.h"
+#include "chip/kl_tsi.h"
+#include "chip/kl_pinmux.h"
+#include "chip/kl_sim.h"
+
+#ifdef CONFIG_KL_TSI
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* The touchpad on the Freedom KL25Z board connects to the MCU via:
+ *
+ * PTB16 TWI0_CH9
+ * PTB17 TSI0_CH10
+ */
+
+#define NSENSORS 2
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static void tsi_calibrate(void);
+static ssize_t tsi_read(FAR struct file *filep, FAR char *buffer, size_t buflen);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static uint16_t g_defcap[NSENSORS]; /* Default capacitance for each sensor */
+static uint16_t g_currdelta = 0; /* Current delta for the current button */
+static uint8_t g_channel = 0; /* Current g_channel */
+
+/* Channel assigned to each sensor */
+
+static uint8_t const g_chsensor[NSENSORS] = { 9, 10 };
+
+/* Character driver operations */
+
+static const struct file_operations tsi_ops =
+{
+ 0, /* open */
+ 0, /* close */
+ tsi_read, /* read */
+ 0, /* write */
+ 0, /* seek */
+ 0, /* ioctl */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: tsi_calibrate
+ ****************************************************************************/
+
+static void tsi_calibrate(void)
+{
+ uint32_t regval;
+ int i;
+
+ for (i = 0; i < NSENSORS; i++)
+ {
+ /* Clear end of scan flag */
+
+ regval = getreg32(KL_TSI_GENCS);
+ regval |= TSI_GENCS_EOSF;
+ putreg32(regval, KL_TSI_GENCS);
+
+ /* Scan the next electrode */
+
+ regval = TSI_DATA_TSICH(g_chsensor[i]);
+ putreg32(regval, KL_TSI_DATA);
+
+ regval |= TSI_DATA_SWTS;
+ putreg32(regval, KL_TSI_DATA);
+
+ /* Wait until the conversion is done */
+
+ while (!(getreg32(KL_TSI_GENCS) & TSI_GENCS_EOSF));
+
+ g_defcap[i] = getreg32(KL_TSI_DATA) & TSI_DATA_TSICNT_MASK;
+ ivdbg("Sensor %d = %d\n", i+1, g_defcap[i]);
+ }
+}
+
+/****************************************************************************
+ * Name: tsi_read
+ ****************************************************************************/
+
+static ssize_t tsi_read(FAR struct file *filep, FAR char *buf, size_t buflen)
+{
+ static int deltacap = 0;
+ uint32_t regval;
+
+ if (buf == NULL || buflen < 1)
+ {
+ /* Well... nothing to do */
+
+ return -EINVAL;
+ }
+
+ deltacap = 0;
+
+ /* Clear end of scan flag */
+
+ regval = getreg32(KL_TSI_GENCS);
+ regval |= TSI_GENCS_EOSF;
+ putreg32(regval, KL_TSI_GENCS);
+
+ /* Scan the next electrode */
+
+ regval = TSI_DATA_TSICH(g_chsensor[g_channel]);
+ putreg32(regval, KL_TSI_DATA);
+
+ regval |= TSI_DATA_SWTS;
+ putreg32(regval, KL_TSI_DATA);
+
+ /* Wait until the conversion is done*/
+
+ while (!(getreg32(KL_TSI_GENCS) & TSI_GENCS_EOSF));
+
+ /* Compute delta using calibration reference counts */
+
+ deltacap = getreg32(KL_TSI_DATA) & TSI_DATA_TSICNT_MASK;
+ deltacap -= g_defcap[g_channel];
+
+ if (deltacap < 0)
+ {
+ deltacap = 0;
+ }
+
+ g_currdelta = (uint16_t)deltacap;
+
+ ivdbg("Delta for g_channel %d = %d\n", g_channel, g_currdelta);
+
+ buf[0] = g_currdelta & 0xff;
+ buf[1] = (g_currdelta & 0xff00) >> 8;
+ buf[2] = g_channel;
+
+ /* Increment the channel index to sample the next sensor on the next timer
+ * that read() is called.
+ */
+
+ g_channel++;
+ if (g_channel >= NSENSORS)
+ {
+ g_channel = 0;
+ }
+
+ return 3;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kl_tsi_initialize
+ *
+ * Description:
+ * Initialize the TSI hardware and interface for the sliders on board the
+ * Freedom KL25Z board. Register a character driver at /dev/tsi that may
+ * be used to read from each sensor.
+ *
+ ****************************************************************************/
+
+void kl_tsi_initialize(void)
+{
+ uint32_t regval;
+
+ /* Enable access to the TSI module */
+
+ regval = getreg32(KL_SIM_SCGC5);
+ regval |= SIM_SCGC5_TSI;
+ putreg32(regval, KL_SIM_SCGC5);
+
+ /* Configure PINs used on TSI */
+
+ kl_configgpio(PIN_TSI0_CH9);
+ kl_configgpio(PIN_TSI0_CH10);
+
+ /* Configure TSI parameter */
+
+ regval = getreg32(KL_TSI_GENCS);
+ regval |= TSI_GENCS_MODE_CAPSENSING | TSI_GENCS_REFCHRG_8UA |
+ TSI_GENCS_DVOLT_1p03V | TSI_GENCS_EXTCHRG_64A |
+ TSI_GENCS_PS_DIV16 | TSI_GENCS_NSCN_TIMES(12) | TSI_GENCS_STPE;
+ putreg32(regval, KL_TSI_GENCS);
+
+ /* Only after setting TSI we should enable it */
+
+ regval = getreg32(KL_TSI_GENCS);
+ regval |= TSI_GENCS_TSIEN;
+ putreg32(regval, KL_TSI_GENCS);
+
+ /* Calibrate it before to use */
+
+ tsi_calibrate();
+
+ /* And finally register the TSI character driver */
+
+ (void)register_driver("/dev/tsi", &tsi_ops, 0444, NULL);
+}
+
+#endif /* CONFIG_KL_TSI */