From 0078252df3a32dbb920e1759c57c0a2b51522efb Mon Sep 17 00:00:00 2001
From: Angus Gratton <gus@projectgus.com>
Date: Mon, 8 Jun 2015 18:09:06 +1000
Subject: [PATCH] Add GPIO config, interrupt registers, GPIO interrupt support,
 'button' example

---
 core/esp_gpio_interrupts.c       |  63 +++++++++++++++
 core/include/esp/gpio.h          |  54 ++++++++++++-
 core/include/esp/registers.h     |  55 ++++++++++---
 examples/blink/blink.c           |   8 +-
 examples/button/FreeRTOSConfig.h | 127 +++++++++++++++++++++++++++++++
 examples/button/Makefile         |   2 +
 examples/button/button.c         |  84 ++++++++++++++++++++
 7 files changed, 377 insertions(+), 16 deletions(-)
 create mode 100644 core/esp_gpio_interrupts.c
 create mode 100644 examples/button/FreeRTOSConfig.h
 create mode 100644 examples/button/Makefile
 create mode 100644 examples/button/button.c

diff --git a/core/esp_gpio_interrupts.c b/core/esp_gpio_interrupts.c
new file mode 100644
index 0000000..9f8a3ae
--- /dev/null
+++ b/core/esp_gpio_interrupts.c
@@ -0,0 +1,63 @@
+/* ESP GPIO interrupts.
+
+   Use with gpio_set_interrupt(), defined in esp/gpio.h
+
+
+   These interrupt vectors are default implementations with weak
+   linkage. Override your own GPIO interrupt vectors in your program
+   and they will replace these.
+
+   Look in examples/button/ for a simple GPIO interrupt example.
+
+   You can implement your own interrupts in two ways:
+
+   - Implement gpXX_interrupt_handler() for the GPIO pin numbers that you want to attach interrupts to. This is simple but it may not be enough sometimes
+
+   - Implement a single gpio_interrupt_handler() and manually check GPIO_STATUS_REG
+     and clear any status bits after handling interrupts. This gives
+     you full control.
+*/
+#include "esp8266.h"
+
+void gpio_interrupt_handler(void);
+void gpio_noop_interrupt_handler(void) { }
+void gpio00_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio01_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio02_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio03_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio04_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio05_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio06_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio07_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio08_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio09_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio10_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio11_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio12_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio13_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio14_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+void gpio15_interrupt_handler(void) __attribute__((weak, alias("gpio_noop_interrupt_handler")));
+
+typedef void (* gpio_interrupt_handler_t)(void);
+
+const gpio_interrupt_handler_t gpio_interrupt_handlers[16] = {
+    gpio00_interrupt_handler, gpio01_interrupt_handler, gpio02_interrupt_handler,
+    gpio03_interrupt_handler, gpio04_interrupt_handler, gpio05_interrupt_handler,
+    gpio06_interrupt_handler, gpio07_interrupt_handler, gpio08_interrupt_handler,
+    gpio09_interrupt_handler, gpio10_interrupt_handler, gpio11_interrupt_handler,
+    gpio12_interrupt_handler, gpio13_interrupt_handler, gpio14_interrupt_handler,
+    gpio15_interrupt_handler };
+
+void __attribute__((weak)) IRAM gpio_interrupt_handler(void)
+{
+    uint32_t status_reg = GPIO_STATUS_REG;
+    GPIO_STATUS_CLEAR = status_reg;
+    uint8_t gpio_idx;
+    while((gpio_idx = __builtin_ffs(status_reg)))
+    {
+	gpio_idx--;
+	status_reg &= ~BIT(gpio_idx);
+	if(GPIO_CTRL_REG(gpio_idx) & GPIO_INT_MASK)
+	    gpio_interrupt_handlers[gpio_idx]();
+    }
+}
diff --git a/core/include/esp/gpio.h b/core/include/esp/gpio.h
index 86cba0c..b7bbd85 100644
--- a/core/include/esp/gpio.h
+++ b/core/include/esp/gpio.h
@@ -10,11 +10,14 @@
 #include <stdbool.h>
 #include "esp/registers.h"
 #include "esp/iomux.h"
+#include "esp/cpu.h"
+#include "xtensa_interrupts.h"
 
 typedef enum {
-    GPIO_INPUT = 0,
-    GPIO_OUTPUT = IOMUX_OE,
-    GPIO_INPUT_PULLUP = IOMUX_PU,
+    GPIO_INPUT,
+    GPIO_OUTPUT,         /* "Standard" push-pull output */
+    GPIO_OUT_OPEN_DRAIN, /* Open drain output */
+    GPIO_INPUT_PULLUP,
 } gpio_direction_t;
 
 /* Enable GPIO on the specified pin, and set it to input/output/ with
@@ -22,7 +25,28 @@ typedef enum {
  */
 INLINED void gpio_enable(const uint8_t gpio_num, const gpio_direction_t direction)
 {
-    iomux_set_gpio_function(gpio_num, (uint8_t)direction);
+    uint32_t iomux_flags;
+    uint32_t ctrl_val;
+
+    switch(direction) {
+    case GPIO_INPUT:
+	iomux_flags = 0;
+	ctrl_val = GPIO_SOURCE_GPIO;
+	break;
+    case GPIO_OUTPUT:
+	iomux_flags = IOMUX_OE;
+	ctrl_val = GPIO_DRIVE_PUSH_PULL|GPIO_SOURCE_GPIO;
+	break;
+    case GPIO_OUT_OPEN_DRAIN:
+	iomux_flags = IOMUX_OE;
+	ctrl_val = GPIO_DRIVE_OPEN_DRAIN|GPIO_SOURCE_GPIO;
+	break;
+    case GPIO_INPUT_PULLUP:
+	iomux_flags = IOMUX_PU;
+	ctrl_val = GPIO_SOURCE_GPIO;
+    }
+    iomux_set_gpio_function(gpio_num, iomux_flags);
+    GPIO_CTRL_REG(gpio_num) = (GPIO_CTRL_REG(gpio_num)&GPIO_INT_MASK) | ctrl_val;
     if(direction == GPIO_OUTPUT)
 	GPIO_DIR_SET = BIT(gpio_num);
     else
@@ -80,5 +104,27 @@ INLINED bool gpio_read(const uint8_t gpio_num)
     return GPIO_IN_REG & BIT(gpio_num);
 }
 
+typedef enum {
+    INT_NONE = 0,
+    INT_RISING = GPIO_INT_RISING,
+    INT_FALLING = GPIO_INT_FALLING,
+    INT_CHANGE = GPIO_INT_CHANGE,
+    INT_LOW = GPIO_INT_LOW,
+    INT_HIGH = GPIO_INT_HIGH,
+} gpio_interrupt_t;
+
+extern void gpio_interrupt_handler(void);
+
+/* Set the interrupt type for a given pin
+ */
+INLINED void gpio_set_interrupt(const uint8_t gpio_num, const gpio_interrupt_t int_type)
+{
+    GPIO_CTRL_REG(gpio_num) = (GPIO_CTRL_REG(gpio_num)&~GPIO_INT_MASK)
+	| (int_type & GPIO_INT_MASK);
+    if(int_type != INT_NONE) {
+	_xt_isr_attach(INUM_GPIO, gpio_interrupt_handler);
+	_xt_isr_unmask(1<<INUM_GPIO);
+    }
+}
 
 #endif
diff --git a/core/include/esp/registers.h b/core/include/esp/registers.h
index fc20888..26e47d5 100644
--- a/core/include/esp/registers.h
+++ b/core/include/esp/registers.h
@@ -17,6 +17,9 @@
 
 typedef volatile uint32_t *esp_reg_t;
 
+/* Internal macro, only defined in header body */
+#define _REG(BASE, OFFSET) (*(esp_reg_t)((BASE)+(OFFSET)))
+
 /* Register base addresses
 
    You shouldn't need to use these directly.
@@ -43,7 +46,7 @@ typedef volatile uint32_t *esp_reg_t;
  * Note that IOMUX register order is _not_ the same as GPIO order. See
  * esp_iomux.h for programmer-friendly IOMUX configuration options
  */
-#define IOMUX_REG(X) *(esp_reg_t)(IOMUX_BASE+4*(X+1))
+#define IOMUX_REG(X) _REG(IOMUX_BASE,0x04+4*X)
 
 #define IOMUX_OE       BIT(0) /* iomux Output enable bit */
 #define IOMUX_OE_SLEEP BIT(1) /* iomux Output during sleep bit */
@@ -85,25 +88,59 @@ typedef volatile uint32_t *esp_reg_t;
  *
  * ... are equivalent, but latter uses less CPU cycles.
  */
-#define GPIO_OUT_REG   *(esp_reg_t)(GPIO0_BASE)
-#define GPIO_OUT_SET   *(esp_reg_t)(GPIO0_BASE+0x04)
-#define GPIO_OUT_CLEAR *(esp_reg_t)(GPIO0_BASE+0x08)
+#define GPIO_OUT_REG   _REG(GPIO0_BASE, 0x00)
+#define GPIO_OUT_SET   _REG(GPIO0_BASE, 0x04)
+#define GPIO_OUT_CLEAR _REG(GPIO0_BASE, 0x08)
 
 /* GPIO DIR registers GPIO_DIR_REG, GPIO_DIR_SET, GPIO_DIR_CLEAR
  *
  * Set bit in DIR register for output pins. Writing to _SET and _CLEAR
  * registers set and clear bits in _REG, respectively.
 */
-#define GPIO_DIR_REG   *(esp_reg_t)(GPIO0_BASE+0x0C)
-#define GPIO_DIR_SET   *(esp_reg_t)(GPIO0_BASE+0x10)
-#define GPIO_DIR_CLEAR *(esp_reg_t)(GPIO0_BASE+0x14)
+#define GPIO_DIR_REG   _REG(GPIO0_BASE, 0x0C)
+#define GPIO_DIR_SET   _REG(GPIO0_BASE, 0x10)
+#define GPIO_DIR_CLEAR _REG(GPIO0_BASE, 0x14)
+
 
 /* GPIO IN register GPIO_IN_REG
  *
  * Reads current input values.
  */
-#define GPIO_IN_REG    *(esp_reg_t)(GPIO0_BASE+0x18)
+#define GPIO_IN_REG    _REG(GPIO0_BASE, 0x18)
 
+/* GPIO interrupt 'status' flag
+
+   Bit set if interrupt has fired (see below for interrupt config
+   registers.
+
+   Lower 16 bits only are used.
+*/
+#define GPIO_STATUS_REG   _REG(GPIO0_BASE,0x1c)
+#define GPIO_STATUS_SET   _REG(GPIO0_BASE,0x20)
+#define GPIO_STATUS_CLEAR _REG(GPIO0_BASE,0x24)
+
+#define GPIO_STATUS_MASK  0x0000FFFFL
+
+/* GPIO pin control registers for GPIOs 0-15
+ *
+ */
+#define GPIO_CTRL_REG(GPNUM) _REG(GPIO0_BASE, 0x28+(GPNUM*4))
+
+#define GPIO_SOURCE_GPIO 0
+#define GPIO_SOURCE_DAC BIT(0) /* "Sigma-Delta" */
+#define GPIO_SOURCE_MASK BIT(0
+
+#define GPIO_DRIVE_PUSH_PULL 0
+#define GPIO_DRIVE_OPEN_DRAIN BIT(2)
+#define GPIO_DRIVE_MASK BIT(2)
+
+#define GPIO_INT_NONE 0
+#define GPIO_INT_RISING BIT(7)
+#define GPIO_INT_FALLING BIT(8)
+#define GPIO_INT_CHANGE (BIT(7)|BIT(8))
+#define GPIO_INT_LOW BIT(9)
+#define GPIO_INT_HIGH (BIT(7)|BIT(9))
+#define GPIO_INT_MASK (BIT(7)|BIT(8)|BIT(9))
 
 /* WDT register(s)
 
@@ -111,6 +148,6 @@ typedef volatile uint32_t *esp_reg_t;
 
    See ROM functions esp_wdt_xxx
  */
-#define WDT_CTRL       *(esp_reg_t)(WDT_BASE)
+#define WDT_CTRL       _REG(WDT_BASE, 0x00)
 
 #endif
diff --git a/examples/blink/blink.c b/examples/blink/blink.c
index bb4abdb..707c173 100644
--- a/examples/blink/blink.c
+++ b/examples/blink/blink.c
@@ -13,7 +13,8 @@ const int gpio = 14;
 /* This task uses the high level GPIO API (esp_gpio.h) to blink an LED.
  *
  * Even though it reads better than the register-level version in blinkenRegisterTask,
- * they compile to the exact same instructions.
+ * they compile to the exact same instructions (except gpio_enable also set the output type in
+ * the GPIO control register).
  */
 void blinkenTask(void *pvParameters)
 {
@@ -32,8 +33,9 @@ void blinkenTask(void *pvParameters)
    It's not fully parameterised, as the IOMUX_SET macro requires the pin number
    as part of the GPxx value.
 
-   This code compiles to the exact same instructions as blinkenTask,
-   so it's probably better to use the blinkenTask version.
+   There is no significant performance benefit to this way over the
+   blinkenTask version, so it's probably better to use the blinkenTask
+   version.
 
    NOTE: This task isn't enabled by default, see the commented out line in user_init.
 */
diff --git a/examples/button/FreeRTOSConfig.h b/examples/button/FreeRTOSConfig.h
new file mode 100644
index 0000000..82ed83d
--- /dev/null
+++ b/examples/button/FreeRTOSConfig.h
@@ -0,0 +1,127 @@
+/*
+    FreeRTOS V7.5.2 - Copyright (C) 2013 Real Time Engineers Ltd.
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that has become a de facto standard.             *
+     *                                                                       *
+     *    Help yourself get started quickly and support the FreeRTOS         *
+     *    project by purchasing a FreeRTOS tutorial book, reference          *
+     *    manual, or both from: http://www.FreeRTOS.org/Documentation        *
+     *                                                                       *
+     *    Thank you!                                                         *
+     *                                                                       *
+    ***************************************************************************
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>!AND MODIFIED BY!<< the FreeRTOS exception.
+
+    >>! NOTE: The modification to the GPL is included to allow you to distribute
+    >>! a combined work that includes FreeRTOS without being obliged to provide
+    >>! the source code for proprietary components outside of the FreeRTOS
+    >>! kernel.
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available from the following
+    link: http://www.freertos.org/a00114.html
+
+    1 tab == 4 spaces!
+
+    ***************************************************************************
+     *                                                                       *
+     *    Having a problem?  Start by reading the FAQ "My application does   *
+     *    not run, what could be wrong?"                                     *
+     *                                                                       *
+     *    http://www.FreeRTOS.org/FAQHelp.html                               *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org - Documentation, books, training, latest versions,
+    license and Real Time Engineers Ltd. contact details.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd license FreeRTOS to High
+    Integrity Systems to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#ifndef FREERTOS_CONFIG_H
+#define FREERTOS_CONFIG_H
+
+/*-----------------------------------------------------------
+ * Application specific definitions.
+ *
+ * These definitions should be adjusted for your particular hardware and
+ * application requirements.
+ *
+ * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
+ * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. 
+ *
+ * See http://www.freertos.org/a00110.html.
+ *----------------------------------------------------------*/
+
+#define configUSE_PREEMPTION		1
+#define configUSE_IDLE_HOOK			0
+#define configUSE_TICK_HOOK			0
+#define configCPU_CLOCK_HZ			( ( unsigned long ) 80000000 )
+#define configTICK_RATE_HZ			( ( portTickType ) 100 )
+#define configMAX_PRIORITIES		( ( unsigned portBASE_TYPE ) 15 )
+#define configMINIMAL_STACK_SIZE	( ( unsigned short )156 )
+#define configTOTAL_HEAP_SIZE		( ( size_t ) ( 32 * 1024 ) )
+#define configMAX_TASK_NAME_LEN		( 16 )
+#define configUSE_TRACE_FACILITY	0
+#define configUSE_STATS_FORMATTING_FUNCTIONS 0
+#define configUSE_16_BIT_TICKS		0
+#define configIDLE_SHOULD_YIELD		1
+
+#define INCLUDE_xTaskGetIdleTaskHandle 1
+#define INCLUDE_xTimerGetTimerDaemonTaskHandle 1
+
+#define configCHECK_FOR_STACK_OVERFLOW  2
+#define configUSE_MUTEXES  1
+#define configUSE_TIMERS    1
+
+#if configUSE_TIMERS
+#define configTIMER_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )
+#define configTIMER_QUEUE_LENGTH (10)
+#define configTIMER_TASK_STACK_DEPTH  ( ( unsigned short ) 512 )
+#endif
+
+/* Co-routine definitions. */
+#define configUSE_CO_ROUTINES 		0
+#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
+
+/* Set the following definitions to 1 to include the API function, or zero
+to exclude the API function. */
+
+#define INCLUDE_vTaskPrioritySet		1
+#define INCLUDE_uxTaskPriorityGet		1
+#define INCLUDE_vTaskDelete				1
+#define INCLUDE_vTaskCleanUpResources	0
+#define INCLUDE_vTaskSuspend			1
+#define INCLUDE_vTaskDelayUntil			1
+#define INCLUDE_vTaskDelay				1
+
+/*set the #define for debug info*/
+#define INCLUDE_xTaskGetCurrentTaskHandle 1
+#define INCLUDE_uxTaskGetStackHighWaterMark 1
+
+#endif /* FREERTOS_CONFIG_H */
+
diff --git a/examples/button/Makefile b/examples/button/Makefile
new file mode 100644
index 0000000..afdbbf0
--- /dev/null
+++ b/examples/button/Makefile
@@ -0,0 +1,2 @@
+TARGET=button
+include ../../common.mk
diff --git a/examples/button/button.c b/examples/button/button.c
new file mode 100644
index 0000000..1579b25
--- /dev/null
+++ b/examples/button/button.c
@@ -0,0 +1,84 @@
+/* Respond to a button press.
+ *
+ * This code combines two ways of checking for a button press -
+ * busy polling (the bad way) and button interrupt (the good way).
+ *
+ * This sample code is in the public domain.
+ */
+#include "espressif/esp_common.h"
+#include "espressif/sdk_private.h"
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "esp8266.h"
+
+/* pin config */
+const int gpio = 0;   /* gpio 0 usually has "PROGRAM" button attached */
+const int active = 0; /* active == 0 for active low */
+const gpio_interrupt_t int_type = INT_FALLING;
+#define GPIO_HANDLER gpio00_interrupt_handler
+
+
+/* This task polls for the button and prints the tick
+   count when it's seen.
+
+   Debounced to 200ms with a simple vTaskDelay.
+
+   This is not a good example of how to wait for button input!
+*/
+void buttonPollTask(void *pvParameters)
+{
+    printf("Polling for button press on gpio %d...\r\n", gpio);
+    while(1) {
+	while(gpio_read(gpio) != active)
+	{
+	    taskYIELD();
+	}
+	printf("Polled for button press at %dms\r\n", xTaskGetTickCount()*portTICK_RATE_MS);
+	vTaskDelay(200 / portTICK_RATE_MS);
+    }
+}
+
+/* This task configures the GPIO interrupt and uses it to tell
+   when the button is pressed.
+
+   The interrupt handler communicates the exact button press time to
+   the task via a queue.
+
+   This is a better example of how to wait for button input!
+*/
+void buttonIntTask(void *pvParameters)
+{
+    printf("Waiting for button press interrupt on gpio %d...\r\n", gpio);
+    xQueueHandle *tsqueue = (xQueueHandle *)pvParameters;
+    gpio_set_interrupt(gpio, int_type);
+
+    uint32_t last = 0;
+    while(1) {
+	uint32_t button_ts;
+	xQueueReceive(*tsqueue, &button_ts, portMAX_DELAY);
+	button_ts *= portTICK_RATE_MS;
+	if(last < button_ts-200) {
+	    printf("Button interrupt fired at %dms\r\n", button_ts);
+	    last = button_ts;
+	}
+    }
+}
+
+static xQueueHandle tsqueue;
+
+void GPIO_HANDLER(void)
+{
+    uint32_t now = xTaskGetTickCountFromISR();
+    xQueueSendToBackFromISR(tsqueue, &now, NULL);
+}
+
+void user_init(void)
+{
+    sdk_uart_div_modify(0, UART_CLK_FREQ / 115200);
+    gpio_enable(gpio, GPIO_INPUT);
+
+    tsqueue = xQueueCreate(2, sizeof(uint32_t));
+    xTaskCreate(buttonIntTask, (signed char *)"buttonIntTask", 256, &tsqueue, 2, NULL);
+    xTaskCreate(buttonPollTask, (signed char*)"buttonPollTask", 256, NULL, 1, NULL);
+}