summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-05-11 16:04:47 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-05-11 16:04:47 -0600
commit5b0a06cafebd0a0dc8060f7e7a4208cac06dcaaa (patch)
treeb3674dc512e2d3b33aa90acbeceecdea3247c341
parent1593bc8ff58f1a833872daec312f326b50bffaf5 (diff)
downloadpx4-nuttx-5b0a06cafebd0a0dc8060f7e7a4208cac06dcaaa.tar.gz
px4-nuttx-5b0a06cafebd0a0dc8060f7e7a4208cac06dcaaa.tar.bz2
px4-nuttx-5b0a06cafebd0a0dc8060f7e7a4208cac06dcaaa.zip
Changes to get the Mikroe STM32F4 touchscreen working from Ken Pettit
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/configs/mikroe-stm32f4/fulldemo/defconfig232
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h6
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/up_touchscreen.c675
-rw-r--r--nuttx/configs/pirelli_dpl10/README.txt70
5 files changed, 697 insertions, 288 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 33f01d1b0..7d6e1ded5 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4699,4 +4699,6 @@
instead of ADC_. From Ken Pettit (2014-5-8).
* configs/olimex-lpc1766stk/tools: Tweaks to support OpenOCD-0.70
(2013-5-10).
+ * configs/mikroe-stm32f4: Changes to get the Mikroelektronika MultiMedia
+ STM32 F4 touchsceen working. From Ken Pettit (2013-5-11).
diff --git a/nuttx/configs/mikroe-stm32f4/fulldemo/defconfig b/nuttx/configs/mikroe-stm32f4/fulldemo/defconfig
index 86aaf26bd..a398f8f73 100644
--- a/nuttx/configs/mikroe-stm32f4/fulldemo/defconfig
+++ b/nuttx/configs/mikroe-stm32f4/fulldemo/defconfig
@@ -148,7 +148,7 @@ CONFIG_STM32_STM32F40XX=y
# STM32 Peripheral Support
#
# CONFIG_STM32_ADC1 is not set
-# CONFIG_STM32_ADC2 is not set
+CONFIG_STM32_ADC2=y
# CONFIG_STM32_ADC3 is not set
# CONFIG_STM32_BKPSRAM is not set
# CONFIG_STM32_CAN1 is not set
@@ -177,7 +177,7 @@ CONFIG_STM32_RNG=y
CONFIG_STM32_SPI2=y
CONFIG_STM32_SPI3=y
CONFIG_STM32_SYSCFG=y
-# CONFIG_STM32_TIM1 is not set
+CONFIG_STM32_TIM1=y
# CONFIG_STM32_TIM2 is not set
# CONFIG_STM32_TIM3 is not set
# CONFIG_STM32_TIM4 is not set
@@ -198,12 +198,13 @@ CONFIG_STM32_USART2=y
# CONFIG_STM32_UART5 is not set
# CONFIG_STM32_USART6 is not set
# CONFIG_STM32_WWDG is not set
+CONFIG_STM32_ADC=y
CONFIG_STM32_SPI=y
#
# Alternate Pin Mapping
#
-# CONFIG_STM32_FLASH_PREFETCH is not set
+CONFIG_STM32_FLASH_PREFETCH=y
# CONFIG_STM32_JTAG_DISABLE is not set
# CONFIG_STM32_JTAG_FULL_ENABLE is not set
# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
@@ -212,6 +213,8 @@ CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
# CONFIG_STM32_FORCEPOWER is not set
CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
# CONFIG_STM32_CCMEXCLUDE is not set
+# CONFIG_STM32_TIM1_PWM is not set
+# CONFIG_STM32_TIM1_ADC is not set
CONFIG_STM32_USART=y
#
@@ -304,7 +307,7 @@ CONFIG_MIKROE_FLASH_PART_LIST="256,768"
CONFIG_MSEC_PER_TICK=10
CONFIG_RR_INTERVAL=200
# CONFIG_SCHED_INSTRUMENTATION is not set
-CONFIG_TASK_NAME_SIZE=0
+CONFIG_TASK_NAME_SIZE=10
# CONFIG_SCHED_HAVE_PARENT is not set
# CONFIG_JULIAN_TIME is not set
CONFIG_START_YEAR=2013
@@ -319,8 +322,9 @@ CONFIG_SDCLONE_DISABLE=y
CONFIG_SCHED_WAITPID=y
# CONFIG_SCHED_STARTHOOK is not set
# CONFIG_SCHED_ATEXIT is not set
-# CONFIG_SCHED_ONEXIT is not set
-CONFIG_USER_ENTRYPOINT="nsh_main"
+CONFIG_SCHED_ONEXIT=y
+CONFIG_SCHED_ONEXIT_MAX=4
+CONFIG_USER_ENTRYPOINT="nxwm_main"
CONFIG_DISABLE_OS_API=y
# CONFIG_DISABLE_CLOCK is not set
# CONFIG_DISABLE_POSIX_TIMERS is not set
@@ -336,6 +340,7 @@ CONFIG_SIG_SIGUSR1=1
CONFIG_SIG_SIGUSR2=2
CONFIG_SIG_SIGALARM=3
CONFIG_SIG_SIGCONDTIMEDOUT=16
+CONFIG_SIG_SIGWORK=17
#
# Sizes of configurable things (0 disables)
@@ -378,11 +383,16 @@ CONFIG_SPI=y
# CONFIG_SPI_OWNBUS is not set
CONFIG_SPI_EXCHANGE=y
# CONFIG_SPI_CMDDATA is not set
-# CONFIG_RTC is not set
+CONFIG_RTC=y
+CONFIG_RTC_DATETIME=y
+CONFIG_RTC_ALARM=y
# CONFIG_WATCHDOG is not set
# CONFIG_ANALOG is not set
# CONFIG_BCH is not set
-# CONFIG_INPUT is not set
+CONFIG_INPUT=y
+# CONFIG_INPUT_TSC2007 is not set
+# CONFIG_INPUT_ADS7843E is not set
+# CONFIG_INPUT_STMPE811 is not set
CONFIG_LCD=y
# CONFIG_LCD_NOGETRUN is not set
CONFIG_LCD_MAXCONTRAST=63
@@ -568,8 +578,8 @@ CONFIG_NX_PACKEDMSFIRST=y
#
# Input Devices
#
-# CONFIG_NX_MOUSE is not set
-# CONFIG_NX_KBD is not set
+CONFIG_NX_MOUSE=y
+CONFIG_NX_KBD=y
#
# Framed Window Borders
@@ -591,10 +601,10 @@ CONFIG_NXFONTS_CHARBITS=7
# CONFIG_NXFONT_SANS22X29 is not set
# CONFIG_NXFONT_SANS28X37 is not set
# CONFIG_NXFONT_SANS39X48 is not set
-# CONFIG_NXFONT_SANS17X23B is not set
-# CONFIG_NXFONT_SANS20X27B is not set
-# CONFIG_NXFONT_SANS22X29B is not set
-# CONFIG_NXFONT_SANS28X37B is not set
+CONFIG_NXFONT_SANS17X23B=y
+CONFIG_NXFONT_SANS20X27B=y
+CONFIG_NXFONT_SANS22X29B=y
+CONFIG_NXFONT_SANS28X37B=y
# CONFIG_NXFONT_SANS40X49B is not set
# CONFIG_NXFONT_SERIF22X29 is not set
# CONFIG_NXFONT_SERIF29X37 is not set
@@ -602,12 +612,32 @@ CONFIG_NXFONTS_CHARBITS=7
CONFIG_NXFONT_SERIF22X28B=y
# CONFIG_NXFONT_SERIF27X38B is not set
# CONFIG_NXFONT_SERIF38X49B is not set
-# CONFIG_NXCONSOLE is not set
+CONFIG_NXCONSOLE=y
+
+#
+# NxConsole Output Text/Graphics Options
+#
+CONFIG_NXCONSOLE_BPP=16
+CONFIG_NXCONSOLE_CURSORCHAR=137
+CONFIG_NXCONSOLE_MXCHARS=128
+CONFIG_NXCONSOLE_CACHESIZE=16
+CONFIG_NXCONSOLE_LINESEPARATION=0
+# CONFIG_NXCONSOLE_NOWRAP is not set
+
+#
+# NxConsole Input options
+#
+# CONFIG_NXCONSOLE_NXKBDIN is not set
+CONFIG_NXCONSOLE_KBDBUFSIZE=16
+CONFIG_NXCONSOLE_NPOLLWAITERS=4
#
# NX Multi-user only options
#
-# CONFIG_NX_MULTIUSER is not set
+CONFIG_NX_MULTIUSER=y
+CONFIG_NX_BLOCKING=y
+CONFIG_NX_MXSERVERMSGS=32
+CONFIG_NX_MXCLIENTMSGS=16
#
# Memory Management
@@ -661,7 +691,12 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
#
# Non-standard Library Support
#
-# CONFIG_SCHED_WORKQUEUE is not set
+CONFIG_SCHED_WORKQUEUE=y
+CONFIG_SCHED_HPWORK=y
+CONFIG_SCHED_WORKPRIORITY=192
+CONFIG_SCHED_WORKPERIOD=20000
+CONFIG_SCHED_WORKSTACKSIZE=2048
+# CONFIG_SCHED_LPWORK is not set
# CONFIG_LIB_KBDCODEC is not set
#
@@ -720,6 +755,15 @@ CONFIG_EXAMPLES_NX_DEFAULT_FONT=y
CONFIG_EXAMPLES_NX_BPP=16
# CONFIG_EXAMPLES_NX_RAWWINDOWS is not set
# CONFIG_EXAMPLES_NX_EXTERNINIT is not set
+
+#
+# Multi-User Configuration Options
+#
+CONFIG_EXAMPLES_NX_STACKSIZE=2048
+CONFIG_EXAMPLES_NX_CLIENTPRIO=100
+CONFIG_EXAMPLES_NX_SERVERPRIO=120
+CONFIG_EXAMPLES_NX_LISTENERPRIO=80
+CONFIG_EXAMPLES_NX_NOTIFYSIGNO=4
# CONFIG_EXAMPLES_NXCONSOLE is not set
# CONFIG_EXAMPLES_NXFFS is not set
# CONFIG_EXAMPLES_NXFLAT is not set
@@ -742,7 +786,10 @@ CONFIG_EXAMPLES_NXIMAGE=y
# CONFIG_EXAMPLES_TELNETD is not set
# CONFIG_EXAMPLES_THTTPD is not set
# CONFIG_EXAMPLES_TIFF is not set
-# CONFIG_EXAMPLES_TOUCHSCREEN is not set
+CONFIG_EXAMPLES_TOUCHSCREEN=y
+CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN=y
+CONFIG_EXAMPLES_TOUCHSCREEN_MINOR=0
+CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH="/dev/input0"
# CONFIG_EXAMPLES_UDP is not set
# CONFIG_EXAMPLES_UIP is not set
# CONFIG_EXAMPLES_USBSERIAL is not set
@@ -860,7 +907,154 @@ CONFIG_NSH_ARCHINIT=y
#
# NxWidgets/NxWM
#
-# CONFIG_NXWIDGETS is not set
+CONFIG_NXWIDGETS=y
+
+#
+# NX Server/Device Configuration
+#
+CONFIG_NXWIDGETS_FLICKERFREE=y
+CONFIG_NXWIDGETS_DEVNO=0
+CONFIG_NXWIDGETS_VPLANE=0
+CONFIG_NXWIDGETS_SERVERPRIO=51
+CONFIG_NXWIDGETS_SERVERSTACK=2048
+CONFIG_NXWIDGETS_CLIENTPRIO=50
+CONFIG_NXWIDGETS_LISTENERPRIO=50
+CONFIG_NXWIDGETS_LISTENERSTACK=2048
+# CONFIG_NXWIDGETS_EXTERNINIT is not set
+# CONFIG_NXWIDGET_EVENTWAIT is not set
+
+#
+# NXWidget Configuration
+#
+CONFIG_NXWIDGETS_BPP=16
+CONFIG_NXWIDGETS_SIZEOFCHAR=1
+
+#
+# NXWidget Default Values
+#
+# CONFIG_NXWIDGETS_SYSTEM_CUSTOM_FONTID is not set
+CONFIG_NXWIDGETS_TNXARRAY_INITIALSIZE=16
+CONFIG_NXWIDGETS_TNXARRAY_SIZEINCREMENT=8
+# CONFIG_NXWIDGETS_CUSTOM_FILLCOLORS is not set
+# CONFIG_NXWIDGETS_CUSTOM_EDGECOLORS is not set
+# CONFIG_NXWIDGETS_CUSTOM_TEXTCOLORS is not set
+CONFIG_NXWIDGETS_TRANSPARENT_COLOR=0x0
+
+#
+# Keypad behavior
+#
+CONFIG_NXWIDGETS_FIRST_REPEAT_TIME=500
+CONFIG_NXWIDGETS_CONTINUE_REPEAT_TIME=200
+CONFIG_NXWIDGETS_DOUBLECLICK_TIME=350
+CONFIG_NXWIDGETS_KBDBUFFER_SIZE=16
+CONFIG_NXWIDGETS_CURSORCONTROL_SIZE=4
+# CONFIG_NXWIDGET_MEMMONITOR is not set
+CONFIG_NXWM=y
+
+#
+# General settings
+#
+# CONFIG_NXWM_SYSTEM_CUSTOM_FONTID is not set
+CONFIG_NXWM_UNITTEST=y
+
+#
+# Color configuration
+#
+# CONFIG_NXWM_CUSTOM_FILLCOLORS is not set
+# CONFIG_NXWM_CUSTOM_EDGECOLORS is not set
+# CONFIG_NXWM_CUSTOM_TEXTCOLORS is not set
+
+#
+# Horizontal and vertical spacing of icons in the task bar
+#
+CONFIG_NXWM_TASKBAR_VSPACING=2
+CONFIG_NXWM_TASKBAR_HSPACING=2
+# CONFIG_NXWM_TASKBAR_TOP is not set
+# CONFIG_NXWM_TASKBAR_BOTTOM is not set
+CONFIG_NXWM_TASKBAR_LEFT=y
+# CONFIG_NXWM_TASKBAR_RIGHT is not set
+# CONFIG_NXWM_CUSTOM_TASKBAR_WIDTH is not set
+# CONFIG_NXWM_DISABLE_MINIMIZE is not set
+# CONFIG_NXWM_TASKBAR_NO_BORDER is not set
+
+#
+# Tool Bar Configuration
+#
+# CONFIG_NXWM_CUSTOM_TOOLBAR_HEIGHT is not set
+
+#
+# Background Image
+#
+# CONFIG_NXWM_DISABLE_BACKGROUND_IMAGE is not set
+CONFIG_NXWM_BACKGROUND_IMAGE=""
+
+#
+# Application Window Configuration
+#
+# CONFIG_NXWM_CUSTOM_APPWINDOW_ICONS is not set
+
+#
+# Start Window Configuration
+#
+
+#
+# Horizontal and vertical spacing of icons in the task bar
+#
+CONFIG_NXWM_STARTWINDOW_VSPACING=4
+CONFIG_NXWM_STARTWINDOW_HSPACING=4
+# CONFIG_NXWM_CUSTOM_STARTWINDOW_ICON is not set
+CONFIG_NXWM_STARTWINDOW_MQNAME="/dev/nxwm"
+CONFIG_NXWM_STARTWINDOW_MXMSGS=32
+CONFIG_NXWM_STARTWINDOW_MXMPRIO=42
+CONFIG_NXWM_STARTWINDOW_PRIO=50
+CONFIG_NXWM_STARTWINDOW_STACKSIZE=2048
+
+#
+# NxConsole Window Configuration
+#
+CONFIG_NXWM_NXCONSOLE_PRIO=50
+CONFIG_NXWM_NXCONSOLE_STACKSIZE=2048
+# CONFIG_NXWM_NXCONSOLE_CUSTOM_COLORS is not set
+# CONFIG_NXWM_NXCONSOLE_CUSTOM_FONTID is not set
+# CONFIG_NXWM_CUSTOM_NXCONSOLE_ICON is not set
+CONFIG_NXWM_TOUCHSCREEN=y
+
+#
+# Touchscreen device settings
+#
+CONFIG_NXWM_TOUCHSCREEN_DEVNO=0
+CONFIG_NXWM_TOUCHSCREEN_DEVPATH="/dev/input0"
+CONFIG_NXWM_TOUCHSCREEN_SIGNO=5
+CONFIG_NXWM_TOUCHSCREEN_LISTENERPRIO=50
+CONFIG_NXWM_TOUCHSCREEN_LISTENERSTACK=1024
+CONFIG_NXWM_KEYBOARD=y
+
+#
+# Keyboard device settings
+#
+CONFIG_NXWM_KEYBOARD_DEVPATH="/dev/ttyS0"
+CONFIG_NXWM_KEYBOARD_SIGNO=6
+CONFIG_NXWM_KEYBOARD_BUFSIZE=16
+CONFIG_NXWM_KEYBOARD_LISTENERPRIO=50
+CONFIG_NXWM_KEYBOARD_LISTENERSTACK=2048
+
+#
+# Calibration display settings
+#
+# CONFIG_NXWM_CALIBRATION_CUSTOM_COLORS is not set
+# CONFIG_NXWM_CUSTOM_CALIBRATION_ICON is not set
+CONFIG_NXWM_CALIBRATION_SIGNO=5
+CONFIG_NXWM_CALIBRATION_LISTENERPRIO=50
+CONFIG_NXWM_CALIBRATION_LISTENERSTACK=2048
+
+#
+# Hex Calculator display settings
+#
+CONFIG_NXWM_HEXCALCULATOR_CUSTOM_COLORS=y
+CONFIG_NXWM_HEXCALCULATOR_BACKGROUNDCOLOR=0x39C7
+# CONFIG_NXWM_CUSTOM_HEXCALCULATOR_ICON is not set
+# CONFIG_NXWM_HEXCALCULATOR_CUSTOM_FONTID is not set
+CONFIG_NXWM_MEDIAPLAYER=y
#
# System NSH Add-Ons
diff --git a/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h b/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h
index 5364d8bd0..d1a69547e 100644
--- a/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h
+++ b/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h
@@ -176,7 +176,11 @@
GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
#define GPIO_TP_DRIVEB (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
- GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
+ GPIO_PORTB|GPIO_PIN9)
+
+#define GPIO_TP_YD (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN0)
+
+#define GPIO_TP_XL (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1)
/****************************************************************************************************
* Public Types
diff --git a/nuttx/configs/mikroe-stm32f4/src/up_touchscreen.c b/nuttx/configs/mikroe-stm32f4/src/up_touchscreen.c
index f7e86fe18..b1caf6cb6 100644
--- a/nuttx/configs/mikroe-stm32f4/src/up_touchscreen.c
+++ b/nuttx/configs/mikroe-stm32f4/src/up_touchscreen.c
@@ -1,10 +1,11 @@
/************************************************************************************
- * configs/pic32mx7mmb/src/up_boot.c
- * arch/mips/src/board/up_boot.c
+ * configs/mikroe-stm32f4/src/up_touchscreen.c
*
* Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
+ * Modified: May, 2013 by Ken Pettit to adapt for Mikroe-STM32M4 board
+ *
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@@ -71,33 +72,43 @@
/* Reference counting is partially implemented, but not needed in the current design.
*/
-#undef CONFIG_TOUCHSCREEN_REFCNT
-
+#define CONFIG_TOUCHSCREEN_REFCNT
/* Should we try again on bad samples? */
#undef CONFIG_TOUCHSCREEN_RESAMPLE
+/* TP uses ADC Channel #2 in a dedicated mode. Ensure ADC2 not selected for general
+ * use via the menuconfig */
+
+#ifndef CONFIG_STM32_ADC2
+# error Touchpanel Input (CONFIG_INPUT=y) requires enablinga ADC2 (CONFIG_STM32_ADC2=y)
+#endif
+
/* Work queue support is required */
#ifndef CONFIG_SCHED_WORKQUEUE
-# warning "Work queue support is required (CONFIG_SCHED_WORKQUEUE=y)
+# warning Work queue support is required (CONFIG_SCHED_WORKQUEUE=y)
#endif
/* CONFIG_TOUCHSCREEN_THRESHX and CONFIG_TOUCHSCREEN_THRESHY
* Touchscreen data comes in a a very high rate. New touch positions
* will only be reported when the X or Y data changes by these thresholds.
* This trades reduces data rate for some loss in dragging accuracy. The
- * touchscreen is configure for 10-bit values so the raw ranges are 0-1023. So
+ * touchscreen is configure for 12-bit values so the raw ranges are 0-4096. So
* for example, if your display is 320x240, then THRESHX=3 and THRESHY=4
* would correspond to one pixel. Default: 4
*/
#ifndef CONFIG_TOUCHSCREEN_THRESHX
-# define CONFIG_TOUCHSCREEN_THRESHX 4
+# define CONFIG_TOUCHSCREEN_THRESHX 12
#endif
#ifndef CONFIG_TOUCHSCREEN_THRESHY
-# define CONFIG_TOUCHSCREEN_THRESHY 4
+# define CONFIG_TOUCHSCREEN_THRESHY 12
+#endif
+
+#ifndef CONFIG_TOUCHSCREEN_AVG_SAMPLES
+# define CONFIG_TOUCHSCREEN_AVG_SAMPLES 2
#endif
/* Driver support *******************************************************************/
@@ -108,44 +119,49 @@
#define DEV_FORMAT "/dev/input%d"
#define DEV_NAMELEN 16
-/* PIC32MX7MMB Touchscreen Hardware Definitions *************************************/
-/* ----- ------ --------------------
- * GPIO ADC IN TFT Signal Name
- * ----- ------ --------------------
- * RB10 AN10 LCD-YD
- * RB11 AN11 LCD-XR
- * RB12 AN12 LCD-YU
- * RB13 AN13 LCD-XL
+/* Mikroe-STM32M4 Touchscreen Hardware Definitions *********************************
+ * PIN CONFIGURATIONS SIGNAL NAME ON-BOARD CONNECTIONS
+ * --- ---------------------------------- -------------------- ------------------------
+ * 35 PB0 LCD-YD YD Analog input
+ * 36 PB1 LCD-XL XL Analog input
+ * 95 PB8 DRIVEA Drives XR, XL and YU
+ * 96 PB9 DRIVEB Drives YD
*/
-#define LCD_XPLUS_PIN (11)
-#define LCD_YPLUS_PIN (12)
-#define LCD_XMINUS_PIN (13)
-#define LCD_YMINUS_PIN (10)
+#define LCD_YD_PIN (0)
+#define LCD_XL_PIN (1)
+#define LCD_YD_CHANNEL (8)
+#define LCD_XL_CHANNEL (9)
+#define LCD_DRIVEA_PIN (8)
+#define LCD_DRIVEB_PIN (9)
+
+#define LCD_DRIVEA_BIT (1 << LCD_DRIVEA_PIN)
+#define LCD_DRIVEB_BIT (1 << LCD_DRIVEB_PIN)
+#define LCD_SAMPX_BITS (LCD_DRIVEA_BIT | (LCD_DRIVEB_BIT << 16))
+#define LCD_SAMPY_BITS (LCD_DRIVEB_BIT | (LCD_DRIVEA_BIT << 16))
+#define LCD_TP_PORT_SETRESET STM32_GPIOB_BSRR
-#define LCD_XPLUS_BIT (1 << LCD_XPLUS_PIN)
-#define LCD_YPLUS_BIT (1 << LCD_YPLUS_PIN)
-#define LCD_XMINUS_BIT (1 << LCD_XMINUS_PIN)
-#define LCD_YMINUS_BIT (1 << LCD_YMINUS_PIN)
-#define LCD_ALL_BITS (LCD_XPLUS_BIT | LCD_YPLUS_BIT | LCD_XMINUS_BIT | LCD_YMINUS_BIT)
+#define TC_ADC_BASE STM32_ADC2_BASE /* ADC Channel base for TP */
+#define ADC_CR1_ALLINTS (ADC_CR1_AWDIE | ADC_CR1_EOCIE | ADC_CR1_JEOCIE)
/* Conversions are performed as 10-bit samples represented as 16-bit unsigned integers: */
-#define MAX_ADC (1023)
+#define MAX_ADC (4096)
/* A measured value has to be within this range to be considered */
-#define UPPER_THRESHOLD (MAX_ADC-1)
-#define LOWER_THRESHOLD (1)
+#define UPPER_THRESHOLD (MAX_ADC-1)
+#define LOWER_THRESHOLD (362)
/* Delays ***************************************************************************/
/* All values will be increased by one system timer tick (probably 10MS). */
-#define TC_PENUP_POLL_TICKS (100 / MSEC_PER_TICK) /* IDLE polling rate: 100 MSec */
-#define TC_PENDOWN_POLL_TICKS (60 / MSEC_PER_TICK) /* Active polling rate: 60 MSec */
-#define TC_DEBOUNCE_TICKS (30 / MSEC_PER_TICK) /* Delay before re-sampling: 30 MSec */
-#define TC_SAMPLE_TICKS (4 / MSEC_PER_TICK) /* Delay for A/D sampling: 4 MSec */
-#define TC_RESAMPLE_TICKS TC_SAMPLE_TICKS
+#define TC_PENUP_POLL_TICKS (70 / MSEC_PER_TICK) /* IDLE polling rate: 100 MSec */
+#define TC_PENDOWN_POLL_TICKS (40 / MSEC_PER_TICK) /* Active polling rate: 60 MSec */
+#define TC_DEBOUNCE_TICKS (16 / MSEC_PER_TICK) /* Delay before re-sampling: 30 MSec */
+#define TC_SAMPLE_TICKS (4 / MSEC_PER_TICK) /* Delay for A/D sampling: 4 MSec */
+#define TC_SETTLE_TICKS (10 / MSEC_PER_TICK) /* Delay for A/D settling: 4 MSec */
+#define TC_RESAMPLE_TICKS TC_SAMPLE_TICKS
/************************************************************************************
* Private Types
@@ -155,13 +171,14 @@
enum tc_state_e
{
TC_READY = 0, /* Ready to begin next sample */
- TC_YMPENDOWN, /* Allowing time for the Y- pen down sampling */
+ TC_READY_SETTLE, /* Allowing time for Y DRIVE to settle */
+ TC_YPENDOWN, /* Allowing time for the Y pen down sampling */
TC_DEBOUNCE, /* Allowing a debounce time for the first sample */
TC_RESAMPLE, /* Restart sampling on a bad measurement */
- TC_YMSAMPLE, /* Allowing time for the Y- sampling */
- TC_YPSAMPLE, /* Allowing time for the Y+ sampling */
- TC_XPSAMPLE, /* Allowing time for the X+ sampling */
- TC_XMSAMPLE, /* Allowing time for the X- sampling */
+ TC_YSAMPLE, /* Allowing time for the Y sampling */
+ TC_XSETTLE, /* Allowing time for the X to settle after changing DRIVE*/
+ TC_XSAMPLE, /* Allowing time for the X sampling */
+ TC_XRESAMPLE, /* Allow time to resample X */
TC_PENDOWN, /* Conversion is complete -- pen down */
TC_PENUP /* Conversion is complete -- pen up */
};
@@ -200,6 +217,8 @@ struct tc_dev_s
volatile bool penchange; /* An unreported event is buffered */
uint16_t value; /* Partial sample value (Y+ or X-) */
uint16_t newy; /* New, un-thresholded Y value */
+ uint8_t sampcount; /* Count of samples for average so far */
+ uint8_t resamplecount; /* Countdown to PENUP */
sem_t devsem; /* Manages exclusive access to this structure */
sem_t waitsem; /* Used to wait for the availability of data */
struct tc_sample_s sample; /* Last sampled touch point data */
@@ -219,12 +238,11 @@ struct tc_dev_s
* Private Function Prototypes
************************************************************************************/
-static void tc_adc_sample(int pin);
-static uint16_t tc_adc_convert(void);
-static void tc_yminus_sample(void);
-static void tc_yplus_sample(void);
-static void tc_xplus_sample(void);
-static void tc_xminus_sample(void);
+static void tc_adc_init(void);
+static void tc_adc_start_sample(int pin);
+static uint16_t tc_adc_read_sample(void);
+static void tc_y_sample(void);
+static void tc_x_sample(void);
static inline bool tc_valid_sample(uint16_t sample);
static void tc_notify(FAR struct tc_dev_s *priv);
@@ -269,198 +287,282 @@ static const struct file_operations tc_fops =
#ifndef CONFIG_TOUCHSCREEN_MULTIPLE
static struct tc_dev_s g_touchscreen;
+static bool g_touchinitdone = false;
#endif
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
- * Name: tc_adc_sample
+ * Name: tc_adc_getreg
*
* Description:
- * Perform A/D sampling. Time must be allowed betwen the start of sampling
- * and conversion (approx. 100Ms).
+ * Read the value of an TC ADC channel (#2) register.
+ *
+ * Input Parameters:
+ * offset - The offset to the register to read
+ * value
+ *
+ * Returned Value:
*
************************************************************************************/
-static void tc_adc_sample(int pin)
+static inline uint32_t tc_adc_getreg(int offset)
{
- /* Configure the pins for as an analog input. AD1PCFG specifies the
- * configuration of device pins to be used as analog inputs. A pin
- * is configured as an analog input when the corresponding PCFGn bit
- * is 0.
+ return getreg32(TC_ADC_BASE + offset);
+}
+
+/************************************************************************************
+ * Name: tc_adc_putreg
+ *
+ * Description:
+ * Set the value of an ADC register.
+ *
+ * Input Parameters:
+ * offset - The offset to the register to read
+ *
+ * Returned Value:
+ *
+ ************************************************************************************/
+
+static inline void tc_adc_putreg(int offset, uint32_t value)
+{
+ putreg32(value, TC_ADC_BASE + offset);
+}
+
+/************************************************************************************
+ * Name: tc_adc_init
+ *
+ * Description:
+ * Initialize ADC Channel #2 for use with the touch panel. The touch panel uses
+ * Channels 8 and 9 (PB0 and PB1) to read the X and Y axis touch positions.
+ *
+ ************************************************************************************/
+
+static void tc_adc_init(void)
+{
+ irqstate_t flags;
+ uint32_t regval;
+
+ /* Do an rcc reset to reset the ADC peripheral */
+
+ /* Disable interrupts. This is necessary because the APB2RTSR register
+ * is used by several different drivers.
*/
- putreg32(ADC_CFG(pin), PIC32MX_ADC_CFGCLR);
+ flags = irqsave();
+
+ /* Enable ADC reset state */
+
+ regval = getreg32(STM32_RCC_APB2RSTR);
+ regval |= RCC_APB2RSTR_ADCRST;
+ putreg32(regval, STM32_RCC_APB2RSTR);
+
+ /* Release ADC from reset state */
+
+ regval &= ~RCC_APB2RSTR_ADCRST;
+ putreg32(regval, STM32_RCC_APB2RSTR);
+
+ /* Initialize the watchdog high threshold register */
+
+ tc_adc_putreg(STM32_ADC_HTR_OFFSET, 0x00000fff);
- /* Set SAMP=0, format 16-bit unsigned integer, manual conversion,
- * SAMP=1 will trigger.
+ /* Initialize the watchdog low threshold register */
+
+ tc_adc_putreg(STM32_ADC_LTR_OFFSET, 0x00000000);
+
+ /* Initialize the same sample time for each ADC 55.5 cycles
+ *
+ * During sample cycles channel selection bits must remain unchanged.
+ *
+ * 000: 1.5 cycles
+ * 001: 7.5 cycles
+ * 010: 13.5 cycles
+ * 011: 28.5 cycles
+ * 100: 41.5 cycles
+ * 101: 55.5 cycles
+ * 110: 71.5 cycles
+ * 111: 239.5 cycles
*/
- putreg32(0, PIC32MX_ADC_CON1);
+ tc_adc_putreg(STM32_ADC_SMPR1_OFFSET, 0x00b6db6d);
+ tc_adc_putreg(STM32_ADC_SMPR2_OFFSET, 0x00b6db6d);
- /* Select the pin as the MUXA CH0 input (positive) */
+ /* ADC CR1 Configuration */
- putreg32(ADC_CHS_CH0SA(pin), PIC32MX_ADC_CHS);
+ regval = tc_adc_getreg(STM32_ADC_CR1_OFFSET);
- /* No input scan */
+ /* Initialize the Analog watchdog enable */
- putreg32(0, PIC32MX_ADC_CSSL);
+ regval &= ~ADC_CR1_AWDEN;
+ regval |= (LCD_YD_CHANNEL << ADC_CR1_AWDCH_SHIFT);
- /* Manual sample, TAD = internal, 6 TPB */
+ /* Enable interrupt flags */
- putreg32(ADC_CON3_ADCS(6) | ADC_CON3_SAMC(0), PIC32MX_ADC_CON3);
+ //regval |= ADC_CR1_ALLINTS;
- /* No interrrupts, no scan, internal voltage reference */
+ /* Disable Overrun interrupt */
- putreg32(ADC_CON2_VCFG_AVDDAVSS, PIC32MX_ADC_CON2);
+ regval &= ~ADC_CR1_OVRIE;
- /* Turn on the ADC */
+ /* Set the resolution of the conversion. We only need 10 bits. */
- putreg32(ADC_CON1_ON, PIC32MX_ADC_CON1SET);
+ regval |= ADC_CR1_RES_12BIT;
- /* Start sampling */
+ tc_adc_putreg(STM32_ADC_CR1_OFFSET, regval);
- putreg32(ADC_CON1_SAMP, PIC32MX_ADC_CON1SET);
-}
+ /* ADC CR2 Configuration */
-/************************************************************************************
- * Name: tc_adc_convert
- *
- * Description:
- * Begin A/D conversion. Time must be allowed betwen the start of sampling
- * and conversion (approx. 100Ms).
- *
- * Assumptions:
- * 1) All output pins configured as outputs:
- * 2) Approprite pins are driven high and low
- *
- ************************************************************************************/
+ regval = tc_adc_getreg(STM32_ADC_CR2_OFFSET);
-static uint16_t tc_adc_convert(void)
-{
- uint32_t retval;
+ /* Clear CONT, continuous mode disable. We will perform single
+ * sampling on one channel at a time. */
+
+ regval &= ~ADC_CR2_CONT;
+
+ /* Set ALIGN (Right = 0) */
- /* Start conversion */
+ regval &= ~ADC_CR2_ALIGN;
- putreg32(ADC_CON1_SAMP, PIC32MX_ADC_CON1CLR);
+ /* External trigger disable. We will do SW triggering */
- /* Wait for the conversion to complete */
+ regval &= ~ADC_CR2_EXTEN_MASK;
- while ((getreg32(PIC32MX_ADC_CON1) & ADC_CON1_DONE) == 0);
+ tc_adc_putreg(STM32_ADC_CR2_OFFSET, regval);
- /* Then read the converted ADC value */
+ /* Configuration of the channel conversion - start with Y sampling */
- retval = getreg32(PIC32MX_ADC_BUF0);
+ regval = tc_adc_getreg(STM32_ADC_SQR3_OFFSET) & ADC_SQR3_RESERVED;
+ regval |= LCD_YD_CHANNEL;
+ tc_adc_putreg(STM32_ADC_SQR3_OFFSET, regval);
+ regval = tc_adc_getreg(STM32_ADC_SQR3_OFFSET);
- /* Disable the ADC */
+ /* Set the number of conversions = 1 */
- putreg32(ADC_CON1_ON, PIC32MX_ADC_CON1CLR);
+ regval = tc_adc_getreg(STM32_ADC_SQR1_OFFSET) & ADC_SQR1_RESERVED;
+ regval |= 0 << ADC_SQR1_L_SHIFT;
+ tc_adc_putreg(STM32_ADC_SQR1_OFFSET, regval);
- /* Reset all pins to digital function */
+ /* ADC CCR configuration */
- putreg32(LCD_ALL_BITS, PIC32MX_ADC_CFGSET);
- return (uint16_t)retval;
+ regval = getreg32(STM32_ADC_CCR);
+ regval &= ~(ADC_CCR_MULTI_MASK | ADC_CCR_DELAY_MASK | ADC_CCR_DDS | ADC_CCR_DMA_MASK |
+ ADC_CCR_ADCPRE_MASK | ADC_CCR_VBATE | ADC_CCR_TSVREFE);
+ regval |= (ADC_CCR_MULTI_NONE | ADC_CCR_DMA_DISABLED | ADC_CCR_ADCPRE_DIV2);
+ putreg32(regval, STM32_ADC_CCR);
+
+ /* Set ADON to wake up the ADC from Power Down state. */
+
+ regval = tc_adc_getreg(STM32_ADC_CR2_OFFSET);
+ regval |= ADC_CR2_ADON;
+ tc_adc_putreg(STM32_ADC_CR2_OFFSET, regval);
+
+ /* Restore the IRQ state */
+
+ irqrestore(flags);
}
/************************************************************************************
- * Name: tc_yminus_sample
+ * Name: tc_adc_start_sample
*
* Description:
- * Initiate sampling on Y-
+ * Perform A/D sampling. Time must be allowed betwen the start of sampling
+ * and conversion (approx. 100Ms).
*
************************************************************************************/
-static void tc_yminus_sample(void)
+static void tc_adc_start_sample(int channel)
{
- /* Configure X- as an input and X+, Y+, and Y- as outputs */
+ uint32_t regval;
- putreg32(LCD_XPLUS_BIT | LCD_YPLUS_BIT | LCD_YMINUS_BIT, PIC32MX_IOPORTB_TRISCLR);
- putreg32(LCD_XMINUS_BIT, PIC32MX_IOPORTB_TRISSET);
+ /* Configure the specified channel for ADC conversion. */
- /* Energize the X plate: Y+ and Y- high, X+ low */
+ regval = tc_adc_getreg(STM32_ADC_SQR3_OFFSET) & ADC_SQR3_RESERVED;
+ regval |= channel;
+ tc_adc_putreg(STM32_ADC_SQR3_OFFSET, regval);
- putreg32(LCD_XPLUS_BIT, PIC32MX_IOPORTB_PORTCLR);
- putreg32(LCD_YPLUS_BIT | LCD_YMINUS_BIT, PIC32MX_IOPORTB_PORTSET);
+ /* Configure the Watchdog for this channel */
- /* Start the Y axis sampling */
+ regval = tc_adc_getreg(STM32_ADC_CR1_OFFSET) & ADC_CR1_AWDCH_MASK;
+ regval |= (channel << ADC_CR1_AWDCH_SHIFT);
+ tc_adc_putreg(STM32_ADC_CR1_OFFSET, regval);
+
+ /* Start the conversion */
- tc_adc_sample(LCD_XMINUS_PIN);
+ regval = tc_adc_getreg(STM32_ADC_CR2_OFFSET);
+ regval |= ADC_CR2_SWSTART;
+ tc_adc_putreg(STM32_ADC_CR2_OFFSET, regval);
}
/************************************************************************************
- * Name: tc_yplus_sample
+ * Name: tc_adc_read_sample
*
* Description:
- * Initiate sampling on Y+
+ * Begin A/D conversion. Time must be allowed betwen the start of sampling
+ * and conversion (approx. 100Ms).
+ *
+ * Assumptions:
+ * 1) All output pins configured as outputs:
+ * 2) Approprite pins are driven high and low
*
************************************************************************************/
-static void tc_yplus_sample(void)
+static uint16_t tc_adc_read_sample(void)
{
- /* Configure X+ as an input and X-, Y+, and Y- as outputs */
+ uint16_t retval;
+ uint32_t adcsr;
+ uint16_t count = 0;
- putreg32(LCD_XMINUS_BIT | LCD_YPLUS_BIT | LCD_YMINUS_BIT, PIC32MX_IOPORTB_TRISCLR);
- putreg32(LCD_XPLUS_BIT, PIC32MX_IOPORTB_TRISSET);
+ /* Validate the conversion is complete */
+
+ adcsr = tc_adc_getreg(STM32_ADC_SR_OFFSET);
+ while ((adcsr & ADC_SR_EOC) == 0)
+ {
+ adcsr = tc_adc_getreg(STM32_ADC_SR_OFFSET);
+ count++;
+ }
- /* Energize the X plate: Y+ and Y- High, X- low (X+ is an input) */
+ /* Read the sample */
- putreg32(LCD_XMINUS_BIT, PIC32MX_IOPORTB_PORTCLR);
- putreg32(LCD_YPLUS_BIT | LCD_YMINUS_BIT, PIC32MX_IOPORTB_PORTSET);
+ retval = tc_adc_getreg(STM32_ADC_DR_OFFSET);
+ retval &= ADC_DR_DATA_MASK;
- /* Start the Y axis sampling */
+ if (count > 0)
+ {
+ idbg("Count = %d\n", count);
+ }
- tc_adc_sample(LCD_XPLUS_PIN);
+ return retval;
}
/************************************************************************************
- * Name: tc_xplus_sample
+ * Name: tc_y_sample
*
* Description:
- * Initiate sampling on X+
+ * Initiate sampling on Y
*
************************************************************************************/
-static void tc_xplus_sample(void)
+static void tc_y_sample(void)
{
- /* Configure Y+ as an input and X+, X-, and Y- as outputs */
-
- putreg32(LCD_XPLUS_BIT | LCD_XMINUS_BIT | LCD_YMINUS_BIT, PIC32MX_IOPORTB_TRISCLR);
- putreg32(LCD_YPLUS_BIT, PIC32MX_IOPORTB_TRISSET);
-
- /* Energize the Y plate: X+ and X- high, Y- low (Y+ is an input) */
-
- putreg32(LCD_YMINUS_BIT, PIC32MX_IOPORTB_PORTCLR);
- putreg32(LCD_XPLUS_BIT | LCD_XMINUS_BIT, PIC32MX_IOPORTB_PORTSET);
-
- /* Read the X axis value */
+ /* Start the Y axis sampling */
- tc_adc_sample(LCD_YPLUS_PIN);
+ tc_adc_start_sample(LCD_XL_CHANNEL);
}
/************************************************************************************
- * Name: tc_xminus_sample
+ * Name: tc_x_sample
*
* Description:
- * Initiate sampling on X-
+ * Initiate sampling on X
*
************************************************************************************/
-static void tc_xminus_sample(void)
+static void tc_x_sample(void)
{
- /* Configure Y- as an input and X+, Y+, and X- as outputs */
-
- putreg32(LCD_XPLUS_BIT | LCD_XMINUS_BIT | LCD_YPLUS_BIT, PIC32MX_IOPORTB_TRISCLR);
- putreg32(LCD_YMINUS_BIT, PIC32MX_IOPORTB_TRISSET);
-
- /* Energize the Y plate: X+ and X- high, Y+ low (Y- is an input) */
+ /* Start the X axis sampling */
- putreg32(LCD_YPLUS_BIT, PIC32MX_IOPORTB_PORTCLR);
- putreg32(LCD_XPLUS_BIT | LCD_XMINUS_BIT, PIC32MX_IOPORTB_PORTSET);
-
- /* Start X axis sampling */
-
- tc_adc_sample(LCD_YMINUS_PIN);
+ tc_adc_start_sample(LCD_YD_CHANNEL);
}
/****************************************************************************
@@ -469,7 +571,7 @@ static void tc_xminus_sample(void)
static inline bool tc_valid_sample(uint16_t sample)
{
- return (sample > LOWER_THRESHOLD /* && sample < UPPER_THRESHOLD */);
+ return (sample > LOWER_THRESHOLD);
}
/****************************************************************************
@@ -482,6 +584,18 @@ static void tc_notify(FAR struct tc_dev_s *priv)
int i;
#endif
+ /* If no threads have the driver open, then just dump the state */
+
+#ifdef CONFIG_TOUCHSCREEN_REFCNT
+ if ((priv->crefs == 0) && priv->sample.contact == CONTACT_UP)
+ {
+ priv->sample.contact = CONTACT_NONE;
+ priv->sample.valid = false;
+ priv->id++;
+ return;
+ }
+#endif
+
/* If there are threads waiting for read data, then signal one of them
* that the read data is available.
*/
@@ -492,7 +606,7 @@ static void tc_notify(FAR struct tc_dev_s *priv)
* is no longer available.
*/
- sem_post(&priv->waitsem);
+ sem_post(&priv->waitsem);
}
/* If there are threads waiting on poll() for touchscreen data to become available,
@@ -592,7 +706,7 @@ static int tc_waitsample(FAR struct tc_dev_s *priv,
while (tc_sample(priv, sample) < 0)
{
/* Wait for a change in the touchscreen state */
-
+
priv->nwaiters++;
ret = sem_wait(&priv->waitsem);
priv->nwaiters--;
@@ -634,9 +748,9 @@ errout:
static void tc_worker(FAR void *arg)
{
FAR struct tc_dev_s *priv = (FAR struct tc_dev_s *)arg;
- uint32_t delay;
+ uint32_t delay = TC_PENUP_POLL_TICKS;
uint16_t value;
- uint16_t newx;
+ uint16_t newx = 0;
int16_t xdiff;
int16_t ydiff;
int ret;
@@ -651,26 +765,47 @@ static void tc_worker(FAR void *arg)
case TC_READY:
{
- /* Start Y- sampling */
+ /* Select DRIVE for Y sampling */
+
+ /* Configure XL, XR with drive voltages and disable YU drive. Note that
+ * this is configuring the DRIVEA and DRIVEB outputs to enable the on-board
+ * transistor drive logic to energize the touch panel.
+ */
+
+ *((uint32_t *) LCD_TP_PORT_SETRESET) = LCD_SAMPY_BITS;
- tc_yminus_sample();
+ /* Allow time for the Y DRIVE to settle */
- /* Allow time for the Y- pend down sampling */
-
- priv->state = TC_YMPENDOWN;
+ priv->resamplecount = 0;
+ priv->sampcount = 0;
+ priv->value = 0;
+ priv->state = TC_READY_SETTLE;
+ delay = TC_SETTLE_TICKS;
+ }
+ break;
+
+ case TC_READY_SETTLE:
+ {
+ /* Start Y sampling */
+
+ tc_y_sample();
+
+ /* Allow time for the Y pend down sampling */
+
+ priv->state = TC_YPENDOWN;
delay = TC_SAMPLE_TICKS;
}
break;
- /* The Y- sampling time has elapsed and the Y- value should be ready
- * for conversion
+ /* The Y sampling time has elapsed and the Y value should be ready
+ * for conversion
*/
- case TC_YMPENDOWN:
+ case TC_YPENDOWN:
{
- /* Convert the Y- sample value */
+ /* Convert the Y sample value */
- value = tc_adc_convert();
+ value = tc_adc_read_sample();
/* A converted value at the minimum would mean that there is no touch
* and that the sampling period is complete.
@@ -683,7 +818,7 @@ static void tc_worker(FAR void *arg)
else
{
/* Allow time for touch inputs to stabilize */
-
+
priv->state = TC_DEBOUNCE;
delay = TC_DEBOUNCE_TICKS;
}
@@ -695,62 +830,45 @@ static void tc_worker(FAR void *arg)
*/
case TC_RESAMPLE:
- case TC_DEBOUNCE:
{
- /* (Re-)start Y- sampling */
+ /* Select DRIVE for Y sampling */
- tc_yminus_sample();
+ /* Configure XL, XR with drive voltages and disable YU drive. Note that
+ * this is configuring the DRIVEA and DRIVEB outputs to enable the on-board
+ * transistor drive logic to energize the touch panel.
+ */
- /* Allow time for the Y- sampling */
-
- priv->state = TC_YMSAMPLE;
- delay = TC_SAMPLE_TICKS;
+ *((uint32_t *) LCD_TP_PORT_SETRESET) = LCD_SAMPY_BITS;
+
+ /* Allow time for the Y DRIVE to settle */
+
+ priv->state = TC_DEBOUNCE;
+ delay = TC_SETTLE_TICKS;
}
break;
- /* The Y- sampling period has elapsed and we are ready to perform the
- * conversion.
- */
-
- case TC_YMSAMPLE:
+ case TC_DEBOUNCE:
{
- /* Convert and save the Y- sample value */
-
- value = tc_adc_convert();
-
- /* A converted value at the minimum would mean that there is no touch
- * and that the sampling period is complete. At converted value at
- * the maximum value is probably bad too.
- */
+ /* (Re-)start Y sampling */
- if (!tc_valid_sample(value))
- {
- priv->state = TC_PENUP;
- }
- else
- {
- /* Save the Y- sample and start Y+ sampling */
+ tc_y_sample();
- priv->value = value;
- tc_yplus_sample();
+ /* Allow time for the Y sampling */
- /* Allow time for the Y+ sampling */
-
- priv->state = TC_YPSAMPLE;
- delay = TC_SAMPLE_TICKS;
- }
+ priv->state = TC_YSAMPLE;
+ delay = TC_SAMPLE_TICKS;
}
break;
- /* The Y+ sampling period has elapsed and we are ready to perform the
+ /* The Y sampling period has elapsed and we are ready to perform the
* conversion.
*/
- case TC_YPSAMPLE: /* Allowing time for the Y+ sampling */
+ case TC_YSAMPLE: /* Allowing time for the Y sampling */
{
- /* Read the Y+ axis position */
+ /* Read the Y axis position */
- value = tc_adc_convert();
+ value = tc_adc_read_sample();
/* A converted value at the minimum would mean that we lost the contact
* before all of the conversions were completed. At converted value at
@@ -768,73 +886,66 @@ static void tc_worker(FAR void *arg)
}
else
{
- value = MAX_ADC - value;
- priv->newy = (value + priv->value) >> 1;
- ivdbg("Y-=%d Y+=%d[%d] Y=%d\n", priv->value, value, MAX_ADC - value, priv->newy);
-
- /* Start X+ sampling */
-
- tc_xplus_sample();
-
- /* Allow time for the X+ sampling */
-
- priv->state = TC_XPSAMPLE;
- delay = TC_SAMPLE_TICKS;
+ value = MAX_ADC - value;
+ priv->value += value;
+ if (++priv->sampcount < CONFIG_TOUCHSCREEN_AVG_SAMPLES)
+ {
+ priv->state = TC_READY_SETTLE;
+ delay = 1;
+ break;
+ }
+
+ priv->newy = value / CONFIG_TOUCHSCREEN_AVG_SAMPLES;
+ priv->value = 0;
+ priv->sampcount = 0;
+ ivdbg("Y=%d\n", priv->newy);
+
+ /* Configure YU and YD with drive voltages and disable XR drive. Note that
+ * this is configuring the DRIVEA and DRIVEB outputs to enable the on-board
+ * transistor drive logic to energize the touch panel.
+ */
+
+ *((uint32_t *) LCD_TP_PORT_SETRESET) = LCD_SAMPX_BITS;
+
+ /* Allow time for the X sampling */
+
+ priv->state = TC_XSETTLE;
+ delay = TC_SETTLE_TICKS;
}
}
break;
- /* The X+ sampling period has elapsed and we are ready to perform the
- * conversion.
- */
-
- case TC_XPSAMPLE:
+ case TC_XRESAMPLE: /* Perform X resampling */
{
- /* Convert the X+ sample value */
-
- value = tc_adc_convert();
-
- /* A converted value at the minimum would mean that we lost the contact
- * before all of the conversions were completed. At converted value at
- * the maximum value is probably bad too.
- */
-
- if (!tc_valid_sample(value))
+ if (priv->resamplecount-- == 0)
{
-#ifdef CONFIG_TOUCHSCREEN_RESAMPLE
- priv->state = TC_RESAMPLE;
- delay = TC_RESAMPLE_TICKS;
-#else
priv->state = TC_PENUP;
-#endif
+ break;
}
- else
- {
- /* Save the X+ sample value */
+ }
- priv->value = value;
+ case TC_XSETTLE: /* Allowing time X to settle after changing DRIVE */
+ {
+ /* The X Drive settling time has elaspsed and it's time to start
+ * the conversion
+ */
- /* Start X- sampling */
+ /* Start X sampling */
- tc_xminus_sample();
+ tc_x_sample();
- /* Allow time for the X- pend down sampling */
-
- priv->state = TC_XMSAMPLE;
- delay = TC_SAMPLE_TICKS;
- }
+ /* Allow time for the X sampling */
+
+ priv->state = TC_XSAMPLE;
+ delay = TC_SAMPLE_TICKS;
}
break;
- /* The X+ sampling period has elapsed and we are ready to perform the
- * conversion.
- */
-
- case TC_XMSAMPLE: /* Allowing time for the X- sampling */
+ case TC_XSAMPLE: /* Allowing time for the X sampling */
{
- /* Read the converted X- axis position */
+ /* Read the converted X axis position */
- value = tc_adc_convert();
+ value = tc_adc_read_sample();
/* A converted value at the minimum would mean that we lost the contact
* before all of the conversions were completed. At converted value at
@@ -844,7 +955,9 @@ static void tc_worker(FAR void *arg)
if (!tc_valid_sample(value))
{
#ifdef CONFIG_TOUCHSCREEN_RESAMPLE
- priv->state = TC_RESAMPLE;
+ priv->state = TC_XRESAMPLE;
+ if (priv->resamplecount == 0)
+ priv->resamplecount = 1;
delay = TC_RESAMPLE_TICKS;
#else
priv->state = TC_PENUP;
@@ -852,11 +965,19 @@ static void tc_worker(FAR void *arg)
}
else
{
- /* Calculate the X- axis position */
+ /* Calculate the X axis position */
- value = MAX_ADC - value;
- newx = (value + priv->value) >> 1;
- ivdbg("X+=%d X-=%d[%d] X=%d\n", priv->value, value, MAX_ADC - value, newx);
+ //value = MAX_ADC - value;
+ priv->value += value;
+ if (++priv->sampcount < CONFIG_TOUCHSCREEN_AVG_SAMPLES)
+ {
+ priv->state = TC_XSETTLE;
+ delay = 1;
+ break;
+ }
+
+ newx = value / CONFIG_TOUCHSCREEN_AVG_SAMPLES;
+ ivdbg("X=%d\n", newx);
/* Samples are available */
@@ -878,7 +999,8 @@ static void tc_worker(FAR void *arg)
* reported. CONTACT_UP == pen up, but not reported)
*/
- if (priv->sample.contact != CONTACT_NONE)
+ if (priv->sample.contact != CONTACT_NONE &&
+ priv->sample.contact != CONTACT_UP)
{
/* The pen is up. We know from the above test, that this is a
* loss of contact condition. This will be changed to CONTACT_NONE
@@ -892,7 +1014,9 @@ static void tc_worker(FAR void *arg)
priv->sample.id = priv->id;
priv->penchange = true;
- /* Notify any waiters that nes touchscreen data is available */
+ /* Notify any waiters that new touchscreen data is available */
+
+ idbg("1:X=%d, Y=%d\n", priv->sample.x, priv->sample.y);
tc_notify(priv);
}
@@ -936,8 +1060,13 @@ static void tc_worker(FAR void *arg)
{
/* There is some change above the threshold... Report the change. */
+#ifdef CONFIG_LCD_LANDSCAPE
+ priv->sample.x = MAX_ADC - priv->newy;
+ priv->sample.y = newx;
+#else
priv->sample.x = newx;
priv->sample.y = priv->newy;
+#endif
priv->sample.valid = true;
/* If this is the first (acknowledged) penddown report, then report
@@ -959,6 +1088,8 @@ static void tc_worker(FAR void *arg)
/* Notify any waiters that nes touchscreen data is available */
+ idbg("2:X=%d, Y=%d\n", priv->sample.x, priv->sample.y);
+
tc_notify(priv);
}
}
@@ -1372,16 +1503,26 @@ int arch_tcinitialize(int minor)
ivdbg("minor: %d\n", minor);
DEBUGASSERT(minor >= 0 && minor < 100);
- /* Configure all touchscreen pins as inputs, undriven */
+ /* If we only have one touchscreen, check if we already did init */
- putreg32(LCD_ALL_BITS, PIC32MX_IOPORTB_TRISSET);
+#ifndef CONFIG_TOUCHSCREEN_MULTIPLE
+ if (g_touchinitdone)
+ {
+ return OK;
+ }
+#endif
- /* Configure all pins for as digital. AD1PCFG specifies the configuration
- * of device pins to be used as analog inputs. A pin is configured as an
- * analog input when the corresponding PCFGn bit is 0.
- */
+ /* Configure the touchscreen DRIVEA and DRIVEB pins for output */
+
+ stm32_configgpio(GPIO_TP_DRIVEA);
+ stm32_configgpio(GPIO_TP_DRIVEB);
- putreg32(LCD_ALL_BITS, PIC32MX_ADC_CFGSET);
+ /* Configure Analog inputs for sampling X and Y coordinates */
+
+ stm32_configgpio(GPIO_TP_XL);
+ stm32_configgpio(GPIO_TP_YD);
+
+ tc_adc_init();
/* Create and initialize a touchscreen device driver instance */
@@ -1428,6 +1569,10 @@ int arch_tcinitialize(int minor)
/* And return success (?) */
+#ifndef CONFIG_TOUCHSCREEN_MULTIPLE
+ g_touchinitdone = true;
+#endif
+
return OK;
errout_with_priv:
diff --git a/nuttx/configs/pirelli_dpl10/README.txt b/nuttx/configs/pirelli_dpl10/README.txt
index 3df496b4a..b53a25917 100644
--- a/nuttx/configs/pirelli_dpl10/README.txt
+++ b/nuttx/configs/pirelli_dpl10/README.txt
@@ -1,10 +1,11 @@
pirelli_dpl10
=============
-This directory contains the board support for Pirelli "Discus" DP-L10 phones.
+This directory contains the board support for Pirelli "Discus" DP-L10
+phones.
-It is a variant of the compal_e88 configuration with the small change of
-enabling the IrDA serial console:
+This port is a variant of the compal_e88 configuration with the small
+change of enabling the IrDA serial console:
* CONFIG_SERIAL_IRDA_CONSOLE=y
@@ -52,3 +53,66 @@ o highram is for phones having the romloader(if the phone has a bootrom)
or for loading in the ram trough a special loader(loaded first on ram
by talking to the ramloader) when having a ramloader(which can only
load 64k).
+
+JTAG and Alternative Serial Console
+===================================
+
+JTAG
+ All JTAG lines, as well as the second uart (UART_MODEM), go to the
+ unpopulated connector next to the display connector.
+
+ --- ---------------------------
+ PIN SIGNAL
+ --- ---------------------------
+ 1 Vcc
+ 2 RX_MODEM
+ 3 TESTRSTz (Iota)
+ 4 TDI
+ 5 TMS
+ 6 TCK
+ 7 TX_MODEM
+ 8 TDO
+ 9 N/C
+ 10 GND
+ 11 N/C
+ 12 N/C
+ --- ---------------------------
+
+JTAG Apapter:
+
+ ------- ----------- --------------- --------------------------------------
+ JTAG 20-PIN DESCRIPTION NOTES
+ SIGNAL CONNECTOR
+ ------- ----------- --------------- --------------------------------------
+ Vcc 1, 2 Vcc
+ nTRST 3 Reset Connect this pin to the (active
+ low) reset input of the target MCU.
+ Some JTAG adapters driver nTRST (high
+ and low). Others can can configure
+ nTRST as open collector (only drive
+ low).
+ GND 4, 6, 8, Ground
+ 10, 12, 14,
+ 16, 20
+ TDI 5 JTAG Test Data Use 10K-100K Ohm pull-up resistor to
+ Input VCC
+ TMS 7 JTAG Test Mode Use 10K-100K Ohm pull-up resistor to
+ Select VCC
+ TCK 9 Clock into the Use 10K-100K Ohm pull-down resistor to
+ core GND
+ RTCK 11 Return clock Some JTAG adapters have adaptive clocking
+ using an RTCK signal.
+ DBGSEL 11 Debug Select Some devices have special pins that
+ enable the JTAG interface. For example,
+ on the NXP LPC2129 the signal RTCK must
+ be driven low during RESET to enable the
+ JTAG interface.
+ TDO 13 JTAG Test Data Use 10K-100K Ohm pull-up resistor to VCC
+ Output
+ DBGRQ 17 N/C
+ DGBACK 19 N/C
+ ISP ?? ISP Most NXP MCU's have an ISP pin which
+ (when pulled low) can be used to cause
+ the MCU to enter a bootloader on reset.
+ Use 10K-100K Ohm pull up resistor.
+ ------- ----------- --------------- --------------------------------------