ESP32 GPIO example using NuttX RTOS (GPIO Interrupt)

This article is a continuation of the series on NuttX RTOS tutorials using the ESP32 Dev board and carries the discussion on NuttX RTOS and their usage. The aim of this series is to provide easy and practical examples that anyone can understand. In our previous tutorial, we saw how to use the GPIO as output. This is the ESP32 GPIO example using NuttX RTOS (GPIO Interrupt). In this tutorial, we will write our own driver and application to use the GPIO as both input and output.

You can also read the FreeRTOS TutorialsESP32 Intro, ESP32 IDF Getting Started, GPIO Linux Device DriverSTM32 RTOS Getting startedBoot sequence in Cortex-M4, and 8051 GPIO Tutorial.

ESP32 GPIO example using NuttX RTOS (GPIO Interrupt)

Prerequisites

To continue with this tutorial, you must have configured the ESP32 toolchain and compiled the NuttX RTOS. If you aren’t configured anything yet, we suggest you to set up the esp32 using the below-given tutorials.

Hardware Required

  • ESP32 Dev board
  • Laptop machine (Host System)
  • LED with Resistor (If you don’t have onboard LED)
  • Any digital input device like a switch, Button, etc. In this example, we have used an IR sensor.

Connection Diagram – ESP32 GPIO example

In this example, we have used ESP32 Pin 18 as an Input pin and Pin 2 as an output pin. So, LED has been connected to Pin 2 and the IR sensor has been connected to Pin 18. Refer to the below connection diagram. You can also connect any digital input device instead of this IR sensor.

ESP32 GPIO example - Connection

Concept of this Driver and Application

In this example, we have used two GPIOs (PIN2 and PIN18). The concept is very simple. When the IR sensor detects any objects in front of it, it will toggle the LED. Refer to the output image for better understanding.

Writing GPIO driver

In the last LED driver code, we have just created open(), close(), write() functions in the driver. But now we need read() and ioctl() functions also. If you are not familiar with the IOCTL function, please read the Linux device driver’s IOCTL. That will give you some idea about the IOCTL. And also in this tutorial, we are going to send the signal from the driver to the application. So, I recommend you to go through this Linux Device Driver’s Signal also to easily understand the concept.

The driver code is pretty simple. We are registering the GPIOs using the IOCTL. If it is an input GPIO and needs interrupt, then we are getting the application’s PID and register the ISR. When the interrupt hits (IR sensor detects anything), we are sending the signal to the application using that PID number that we have got it from the IOCTL.

If it is an output GPIO, then we just configure that GPIO as output and change the GPIO state in the write function. Once you are done with the GPIOs, then you can just unregister the GPIOs using the IOCTL.

We are going to create a file under /dev/In our example, our driver will create the /dev/etx_gpio file.

First, let’s see the code below.

esp32_etx_gpio.c

I have added this file to the nuttx/boards/xtensa/esp32/common/src/.

/****************************************************************************
 * boards/xtensa/esp32/common/src/esp32_etx_gpio.c
 *
 * Licensed to the Apache Software Foundation (ASF) under one or more
 * contributor license agreements.  See the NOTICE file distributed with
 * this work for additional information regarding copyright ownership.  The
 * ASF licenses this file to you under the Apache License, Version 2.0 (the
 * "License"); you may not use this file except in compliance with the
 * License.  You may obtain a copy of the License at
 *
 *   http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
 * License for the specific language governing permissions and limitations
 * under the License.
 *
 ****************************************************************************/

/****************************************************************************
 * Included Files
 ****************************************************************************/

#include <nuttx/config.h>

#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <assert.h>

#include <nuttx/board.h>
#include <arch/board/board.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <arch/irq.h>
#include <nuttx/signal.h>
#include "esp32-devkitc.h"
#include "esp32_gpio.h"
#include "esp32_etx_gpio.h"

#ifdef CONFIG_ESP32_ETX_GPIO

#define INVALID_GPIO 0xFF     //invalid GPIO

/****************************************************************************
 * Private Function Prototypes
 ****************************************************************************/

/* Character driver methods */

static int     etx_gpio_open(FAR struct file *filep);
static int     etx_gpio_close(FAR struct file *filep);
static ssize_t etx_gpio_write(FAR struct file *filep, FAR const char *buffer,
                        size_t buflen);
static ssize_t etx_gpio_read(FAR struct file *filep, FAR char *buffer,
                         size_t len);
static int etx_gpio_ioctl(FAR struct file *filep, int cmd, unsigned long arg);

/****************************************************************************
 * Private Data
 ****************************************************************************/

struct sigevent event  = { 0 };
pid_t  pid;

static const struct file_operations etx_gpio_fops =
{
  etx_gpio_open,   /* open   */
  etx_gpio_close,  /* close  */
  etx_gpio_read,   /* read   */
  etx_gpio_write,  /* write  */
  NULL,            /* seek   */
  etx_gpio_ioctl,  /* ioctl  */
  NULL,            /* poll   */
#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS
  NULL             /* unlink */
#endif
};

/****************************************************************************
 * Private Functions
 ****************************************************************************/
 /****************************************************************************
 * Name: etx_gpio_ISR
 *
 * Description:
 *   Interrupt Service Routine.
 ****************************************************************************/

static int etx_gpio_ISR(int irq, void *context, void *arg)
{
  if ( pid )
  {
    struct sigevent signal;
    
    signal.sigev_notify = SIGEV_SIGNAL;
    signal.sigev_signo  = ETX_GPIO_SIGNO;
    signal.sigev_value.sival_int = 1;
    
    /* send signal to the application */
    nxsig_notification(pid, &signal, SI_QUEUE, NULL);
  }
  
  return OK;
}

/****************************************************************************
 * Name: etx_gpio_open
 *
 * Description:
 *   Standard character driver open method.
 *
 *	This function will be getting called when the application
 *	opens the "/dev/etx_gpio" file.
 ****************************************************************************/

static int etx_gpio_open(FAR struct file *filep)
{
  int ret = 0;

  return ( ret );
}

/****************************************************************************
 * Name: etx_gpio_close
 *
 * Description:
 *   Standard character driver close method.
 *
 *	This function will be getting called when the application
 *	closess the "/dev/etx_gpio" file.
 ****************************************************************************/

static int etx_gpio_close(FAR struct file *filep)
{
  int ret = 0;

  return ( ret );
}

/****************************************************************************
 * Name: etx_gpio_write
 *
 * Description:
 *   Standard character driver write method.
 *
 *	This function will be getting called when the application
 *	writes data the "/dev/etx_gpio" file.
 ****************************************************************************/

static ssize_t etx_gpio_write(FAR struct file *filep, FAR const char *buffer,
                             size_t len)
{
  DEBUGASSERT(buffer != NULL);
  
  etx_gpio *gpio = (FAR etx_gpio *)((uintptr_t)buffer);
  
  if( gpio->gpio_num < 0 || gpio->gpio_num > ESP32_NGPIOS )
  {
    syslog(LOG_ERR, "Write: Invalid GPIO Number - %d\n", gpio->gpio_num);
    return ( len );
  }
  
  // Write to the GPIO
  esp32_gpiowrite( gpio->gpio_num, *gpio->gpio_value );
    
  return ( len );
}

/****************************************************************************
 * Name: etx_gpio_read
 *
 * Description:
 *  Standard character driver read method.
 *
 *	This function will be getting called when the application
 *	reads data from the "/dev/etx_gpio" file.
 *
 ****************************************************************************/

static ssize_t etx_gpio_read(FAR struct file *filep, FAR char *buffer,
                         size_t len)
{
  int ret = 0;
  
  DEBUGASSERT(buffer != NULL);

  etx_gpio *gpio = (FAR etx_gpio *)( (uintptr_t)buffer );
  
  if( gpio->gpio_num < 0 || gpio->gpio_num > ESP32_NGPIOS )
  {
    syslog(LOG_ERR, "Read: Invalid GPIO Number - %d\n", gpio->gpio_num);
    return ( ret );
  }
   
  *gpio->gpio_value  = esp32_gpioread( gpio->gpio_num );
    
  return ( ret );
}

/****************************************************************************
 * Name: etx_gpio_ioctl
 *
 * Description:
 *   Standard character driver ioctl method.
 *
 *	This function will be getting called when the application
 *	do IOCTL call to the "/dev/etx_gpio" file.
 *
 ****************************************************************************/

static int etx_gpio_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
  int ret = 0;
  etx_gpio gpio;
  
  DEBUGASSERT( (FAR void *)arg != NULL );
  
  //copy the GPIO struct
  memcpy( &gpio, (FAR void *)arg, sizeof(etx_gpio) );
  
  if( gpio.gpio_num < 0 || gpio.gpio_num > ESP32_NGPIOS )
  {
    syslog(LOG_ERR, "IOCTL: Invalid GPIO Number - %d\n", gpio.gpio_num);
    return ( -1 );
  }
  
  switch( cmd )
  {    
    case GPIOC_REGISTER:
    {      
      if( gpio.gpio_type == ETX_GPIO_IN )
      {
        // Configure the GPIO as output
        esp32_configgpio( gpio.gpio_num , INPUT );
      }
      else if( gpio.gpio_type == ETX_GPIO_OUT )
      {
        // Configure the GPIO as output
        esp32_configgpio( gpio.gpio_num , OUTPUT );
      }
      else if( gpio.gpio_type == ETX_GPIO_IN_INT )
      {
      	pid = getpid();
      	
        // Configure the GPIO as interrupt pin
        int irq = ESP32_PIN2IRQ(gpio.gpio_num);
        esp32_configgpio( gpio.gpio_num , INPUT_FUNCTION_3 | PULLUP );
        ret = irq_attach(irq, etx_gpio_ISR, NULL);
        if( ret >= 0 )
        {
          esp32_gpioirqenable(irq, ONHIGH);
        }
      }
      else
      {
        // Invalid operation
        ret = -1;
      }
      
    }
    break;
    
    case GPIOC_UNREGISTER:
    {
      /* Unregister the GPIO */
      if( gpio.gpio_type == ETX_GPIO_IN_INT )
      {
        // unregister the interrupt pin
        int irq = ESP32_PIN2IRQ(gpio.gpio_num);
        esp32_gpioirqdisable(irq);
        pid = 0;
      }
    }
    break;
    
    default:
      ret = -1;
      break;
  }

  return ( ret );
}

/****************************************************************************
 * Public Functions
 ****************************************************************************/

/****************************************************************************
 * Name: etx_gpio_driver_init
 *
 * Description:
 *   Initialize the EmbeTronicX GPIO device Driver. 
 *   This will create the device file as "/dev/etx_gpio"
 * 
 *   return negative number on failure.
 *   return 0 on success.
 *
 ****************************************************************************/

int etx_gpio_driver_init( void )
{
  int ret = 0;
  ret = register_driver("/dev/etx_gpio", &etx_gpio_fops, 0666, NULL);
  if (ret < 0)
  {
    _err("ERROR: register_driver failed : /dev/etx_gpio : %d\n", ret);
    ret = -1;;
  }

  return ( ret );

}

#endif /* CONFIG_ESP32_ETX_GPIO */

 

esp32_etx_gpio.h

I have added this file to the path nuttx/boards/xtensa/esp32/common/include/.

/****************************************************************************
 * boards/xtensa/esp32/common/include/esp32_etx_gpio.h
 *
 * Licensed to the Apache Software Foundation (ASF) under one or more
 * contributor license agreements.  See the NOTICE file distributed with
 * this work for additional information regarding copyright ownership.  The
 * ASF licenses this file to you under the Apache License, Version 2.0 (the
 * "License"); you may not use this file except in compliance with the
 * License.  You may obtain a copy of the License at
 *
 *   http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
 * License for the specific language governing permissions and limitations
 * under the License.
 *
 ****************************************************************************/

#ifndef __BOARDS_XTENSA_ESP32_COMMON_INCLUDE_ETX_GPIO_H
#define __BOARDS_XTENSA_ESP32_COMMON_INCLUDE_ETX_GPIO_H

/****************************************************************************
 * Included Files
 ****************************************************************************/

#include <nuttx/config.h>
#include <sys/ioctl.h>

#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif

#define GPIOC_REGISTER   _GPIOC(1)              // IOCTL command to register
#define GPIOC_UNREGISTER _GPIOC(2)              // IOCTL command to unregister

#define ETX_GPIO_SIGNO   SIGUSR1                // Signal number 

typedef enum
{
  ETX_GPIO_IN,        // GPIO as input
  ETX_GPIO_OUT,       // GPIO as ouput
  ETX_GPIO_IN_INT     // GPIO as input and enable the interrupt
} GPIO_TYPE;

typedef struct
{
  GPIO_TYPE gpio_type;    // GPIO type
  uint8_t   gpio_num;     // GPIO number
  uint8_t  *gpio_value;   // GPIO value
  void     *data;         // Data
}etx_gpio;

/****************************************************************************
 * Name: etx_gpio_driver_init
 *
 * Description:
 *   Initialize the EmbeTronicX gpio device Driver. 
 *   This will create the device file as "/dev/etx_gpio"
 *
 *   return negative number on failure.
 *   return 0 on success.
 * 
 ****************************************************************************/

#ifdef CONFIG_ESP32_ETX_GPIO
int etx_gpio_driver_init( void );
#endif



#undef EXTERN
#ifdef __cplusplus
}
#endif

#endif /* __BOARDS_XTENSA_ESP32_COMMON_INCLUDE_ETX_GPIO_H */

There is a function called etx_gpio_driver_init()that is a starting point of the driver and it registers the driver and it creates the device file called /dev/etx_gpio. This function has to be called from somewhere initially. To do that, we are calling this function from the esp32_bringup.c.

I am adding the below code into the nuttx/boards/xtensa/esp32/esp32-devkitc/src/esp32_bringup.c‘s esp32_bringup() function.

#ifdef CONFIG_ESP32_ETX_GPIO
#include "esp32_etx_gpio.h"
#endif

#ifdef CONFIG_ESP32_ETX_GPIO
  /* Register the EmbeTronicX GPIO Driver */

  ret = etx_gpio_driver_init();
  if (ret < 0)
    {
      syslog(LOG_ERR, "ERROR: etx_gpio_driver_init() failed: %d\n", ret);
    }
#endi

Makefile

Now we have to build this driver. So, we have to add the below lines into the nuttx/boards/xtensa/esp32/common/src/Make.defs

ifeq ($(CONFIG_ESP32_ETX_GPIO),y)
  CSRCS += esp32_etx_gpio.c
endif

Kconfig

Till now, we are ready with the GPIO driver. But if we add an option to enable/disable this driver during the build, it would be very good. So, to do that, I am adding the below lines into the nuttx/boards/xtensa/esp32/common/Kconfig.

config ESP32_ETX_GPIO
  bool "EmbeTronicX GPIO driver"
  default n
  ---help---
    Enables the GPIO driver to control the GPIOs (ESP32).

    This is added by the EmbeTroincX to demonstrate the
    GPIO control using the ESP32 Dev board with NuttX.

    This includes the EmbeTronicX GPIO driver which controls 
    the GPIO.

That’s all about the driver. Let’s write our application to access this driver. You can check the driver changes that I have added as part of this tutorial in the GitHub commit. And you can get the complete source code from GitHub.

Writing GPIO Application

In application, I am going to create a task called “ETX_GPIO” using the task_create() function. Then in the task, I am registering the GPIOs using the IOCTL call and registering the signal handler. So, whenever the Driver sends the signal, this signal handler will be triggered.

etx_gpio_app.c

I am creating a new directory called etx_gpio under apps/examples

/****************************************************************************
 * examples/etx_gpio/etx_gpio_app.c
 *
 * Licensed to the Apache Software Foundation (ASF) under one or more
 * contributor license agreements.  See the NOTICE file distributed with
 * this work for additional information regarding copyright ownership.  The
 * ASF licenses this file to you under the Apache License, Version 2.0 (the
 * "License"); you may not use this file except in compliance with the
 * License.  You may obtain a copy of the License at
 *
 *   http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
 * License for the specific language governing permissions and limitations
 * under the License.
 *
 ****************************************************************************/

/****************************************************************************
 * Included Files
 ****************************************************************************/

#include <nuttx/config.h>

#include <stdbool.h>
#include <stdlib.h>
#include <stdio.h>
#include <fcntl.h>
#include <sched.h>
#include <errno.h>
#include <sys/ioctl.h>
#include <nuttx/signal.h>

#ifdef CONFIG_EXAMPLES_ETX_GPIO

#define ETX_GPIO_DRIVER_PATH "/dev/etx_gpio"    // GPIO Driver path

#define ETX_INPUT_GPIO_NUM   18                 // Input GPIO number
#define ETX_OUTPUT_GPIO_NUM  02                 // Output GPIO number

/****************************************************************************
 * Private Data
 ****************************************************************************/
#define GPIOC_REGISTER   _GPIOC(1)              // IOCTL command to register
#define GPIOC_UNREGISTER _GPIOC(2)              // IOCTL command to unregister

#define ETX_GPIO_SIGNO   SIGUSR1                // Signal number 

typedef enum
{
  ETX_GPIO_IN,        // GPIO as input
  ETX_GPIO_OUT,       // GPIO as ouput
  ETX_GPIO_IN_INT     // GPIO as input and enable the interrupt
} GPIO_TYPE;

typedef struct
{
  GPIO_TYPE gpio_type;    // GPIO type
  uint8_t   gpio_num;     // GPIO number
  uint8_t  *gpio_value;   // GPIO value
  void     *data;         // Data
}etx_gpio;

static bool is_signal_received = false;

static etx_gpio gpio_in;

static etx_gpio gpio_out;

static uint64_t oldTime;

/****************************************************************************
 * Private Functions
 ****************************************************************************/

/****************************************************************************
 * Name: etx_signal_handler
 ****************************************************************************/

static void etx_signal_handler(int signo, FAR siginfo_t *info, FAR void *ucontext)
{
  /* This if check is to eliminate the spurious interrupts.
  ** Added software debounce mechanism.
  */
  if(( g_system_timer - oldTime ) > 20 ) 
  {
    oldTime = g_system_timer;
    printf("Signal received from the etx_gpio driver\n");
    is_signal_received = true;
  }
}
/****************************************************************************
 * Name: etx_gpio_task
 ****************************************************************************/

static int etx_gpio_task(int argc, char *argv[])
{
  int ret = 0;
  struct sigaction act = { 0 };
  struct sigaction oact;
  uint8_t gpio_in_val;
  uint8_t gpio_out_val;

  printf("ETX_GPIO: Task Starting\n");

  int fd = open( ETX_GPIO_DRIVER_PATH, O_WRONLY);
  if (fd < 0)
  {
    printf("ETX_GPIO:ERROR - Failed to open %s: %d\n", ETX_GPIO_DRIVER_PATH, errno);
    ret = -1;
  }

  /* Register signal handler */
  act.sa_sigaction = etx_signal_handler;
  act.sa_flags     = SA_SIGINFO;
  sigemptyset(&act.sa_mask);
  sigfillset(&act.sa_mask);
  sigdelset(&act.sa_mask, ETX_GPIO_SIGNO);

  ret = sigaction(ETX_GPIO_SIGNO, &act, &oact);
  if (ret < 0)
  {
    int errcode = errno;
    printf("ETX_GPIO: ERROR: sigaction failed: %d\n", errcode);
  }

  /* Register the Input GPIO */
  gpio_in.gpio_type  = ETX_GPIO_IN_INT;
  gpio_in.gpio_num   = ETX_INPUT_GPIO_NUM;
  gpio_in.gpio_value = &gpio_in_val;
  gpio_in.data       = NULL;

  if( ret >= 0 )
  {
    ret = ioctl(fd, GPIOC_REGISTER, (unsigned long)((uintptr_t)&gpio_in));
    if (ret < 0)
    {
      int errcode = errno;
      printf("ETX_GPIO: ERROR: GPIOC_REGISTER ioctl failed: %d\n", errcode);
    }
  }

  /* Register the Output GPIO */
  gpio_out.gpio_type  = ETX_GPIO_OUT;
  gpio_out.gpio_num   = ETX_OUTPUT_GPIO_NUM;
  gpio_out.gpio_value = &gpio_out_val;
  gpio_out.data       = NULL;

  if( ret >= 0 )
  {
    ret = ioctl(fd, GPIOC_REGISTER, (unsigned long)((uintptr_t)&gpio_out));
    if (ret < 0)
    {
      int errcode = errno;
      printf("ETX_GPIO: ERROR: GPIOC_REGISTER ioctl failed: %d\n", errcode);
    }
  }

  while( ret >= 0 )
  {
    if( is_signal_received == true )
    {
      //toggle the gpio val
      gpio_out_val = !gpio_out_val;

      //write the GPIO value to the driver
      ret = write( fd, (const void*)&gpio_out, sizeof(gpio_out) );
      is_signal_received = false;
    }
    usleep(50);
  }

  /* Unregister the GPIOs */
  ret = ioctl(fd, GPIOC_UNREGISTER, (unsigned long)((uintptr_t)&gpio_in));
  if (ret < 0)
  {
    int errcode = errno;
    printf("ETX_GPIO: ERROR: GPIOC_UNREGISTER ioctl failed: %d\n", errcode);
    ret = -1;
  }

  ret = ioctl(fd, GPIOC_REGISTER, (unsigned long)((uintptr_t)&gpio_out));
  if (ret < 0)
  {
    int errcode = errno;
    printf("ETX_GPIO: ERROR: GPIOC_UNREGISTER ioctl failed: %d\n", errcode);
    ret = -1;
  }

  close(fd);
  printf("ETX_GPIO: ERROR - Task finishing\n");
  return EXIT_FAILURE;
}

/****************************************************************************
 * Public Functions
 ****************************************************************************/

/****************************************************************************
 * main
 ****************************************************************************/

int main(int argc, FAR char *argv[])
{
  int ret;

  printf("ETX_GPIO: Starting the Application\n");


  ret = task_create( "ETX_GPIO",                         // Task Name
                     CONFIG_EXAMPLES_ETX_GPIO_PRIORITY,  // Task priority
                     CONFIG_EXAMPLES_ETX_GPIO_STACKSIZE, // Task Stack size
                     etx_gpio_task,                      // Task function
                     NULL
                   );
  if (ret < 0)
  {
    int errcode = errno;
    printf("ETX_GPIO: ERROR: Failed to start ETX GPIO task: %d\n", errcode);
    return EXIT_FAILURE;
  }

  return EXIT_SUCCESS;
}

#endif //#ifdef CONFIG_EXAMPLES_ETX_GPIO

Along with the etx_gpio_app.c, I am creating the three more files called MakefileMake.defs, and Kconfig into the apps/examples/etx_gpio directory.

Makefile

############################################################################
# apps/examples/etx_gpio/Makefile
#
# Licensed to the Apache Software Foundation (ASF) under one or more
# contributor license agreements.  See the NOTICE file distributed with
# this work for additional information regarding copyright ownership.  The
# ASF licenses this file to you under the Apache License, Version 2.0 (the
# "License"); you may not use this file except in compliance with the
# License.  You may obtain a copy of the License at
#
#   http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
# License for the specific language governing permissions and limitations
# under the License.
#
############################################################################

include $(APPDIR)/Make.defs

# ETX GPIO built-in application info

PROGNAME  = $(CONFIG_EXAMPLES_ETX_GPIO_PROGNAME)
PRIORITY  = $(CONFIG_EXAMPLES_ETX_GPIO_PRIORITY)
STACKSIZE = $(CONFIG_EXAMPLES_ETX_GPIO_STACKSIZE)
MODULE    = $(CONFIG_EXAMPLES_ETX_GPIO)

# ETX GPIO Example

MAINSRC = etx_gpio_app.c

include $(APPDIR)/Application.mk

Make.defs

############################################################################
# apps/examples/etx_gpio/Make.defs
#
# Licensed to the Apache Software Foundation (ASF) under one or more
# contributor license agreements.  See the NOTICE file distributed with
# this work for additional information regarding copyright ownership.  The
# ASF licenses this file to you under the Apache License, Version 2.0 (the
# "License"); you may not use this file except in compliance with the
# License.  You may obtain a copy of the License at
#
#   http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
# License for the specific language governing permissions and limitations
# under the License.
#
############################################################################

ifneq ($(CONFIG_EXAMPLES_ETX_GPIO),)
CONFIGURED_APPS += $(APPDIR)/examples/etx_gpio
endif

Kconfig

#
# For a description of the syntax of this configuration file,
# see the file kconfig-language.txt in the NuttX tools repository.
#

config EXAMPLES_ETX_GPIO
  tristate "EmbeTronicX GPIO app example"
  default n
  depends on ESP32_ETX_GPIO
  ---help---
    Enable the EmbeTronicX GPIO app example

if EXAMPLES_ETX_GPIO

config EXAMPLES_ETX_GPIO_PROGNAME
  string "Program name"
  default "etx_gpio"
  ---help---
    This is the name of the program that will be used when the NSH ELF
    program is installed.

config EXAMPLES_ETX_GPIO_PRIORITY
  int "etx_gpio task priority"
  default 100

config EXAMPLES_ETX_GPIO_STACKSIZE
  int "etx_gpio stack size"
  default DEFAULT_TASK_STACKSIZE

endif

You can check the application changes that I have added as part of this tutorial in the GitHub commit. And you can get the complete source code from GitHub.

Building the driver and app

Let’s build our app and the driver together. I have created the build.sh shell script to combine all the required steps into one file.

build.sh

This build.sh has been added into the nuttx/ directory. You can get the build.sh from GitHub.

# !/bin/bash

# A simple bash script to build the NuttX RTOS

#export ESP32 env
. $HOME/esp/esp-idf/export.sh


if [ $1 -eq 1 ]
then
  #distclean
  echo "Dist clean"
  make distclean
  
  #ESP32 configure
  echo "configuring ESP32 with NuttX RTOS"
  ./tools/configure.sh esp32-devkitc:nsh
fi

#menuconfig
make menuconfig

#make and flash
make download ESPTOOL_PORT=/dev/ttyUSB0

The above script has one argument. If you pass 1, then it does distclean and initializes the board configs. If you pass other than 1, then it does only the make menuconfig and make.

I don’t want to do the distclean. So, just building the NuttX. Run the below command in NuttX/nuttx directory.

etx@etx-VirtualBox:~/NuttX/nuttx$. ./build.sh 0

When you run the above command, you should get the menuconfig window. In that menuconfig, we have to enable the etx_gpio driver and the etx_gpio_app application.

Just navigate to Board Selection —> EmbeTronicX Drivers —> and check (enable) the EmbeTroincX GPIO driver like the below image.

Enable EmbeTronicX GPIO driver

Then after that, enable the GPIO interrupts by navigating to Home —> System Type —> enable the GPIO pin interrupts like the below image.

Enable GPIO Interrupts

Then let’s enable the GPIO app by navigating to Home —> Application Configuration —> Examples —> and enable the EmbeTronicX GPIO app example. Please refer to the below image.

Enable GPIO app

That’s all. Let’s build the NuttX now.

Save and Exit the menuconfig and let it build. Once it is trying to connect, hold the BOOT button. Then it will start flashing.

Once you build and flashed it, you connect the device using the picocom using the picocom -b 115200 /dev/ttyUSB0 command.

Now you will get the NuttShell (nsh). Enter the ? or help command. You will get the etx_gpio app. Now run the etx_gpio app.

Output – ESP32 GPIO example using NuttX RTOS

Once booting is done, you run the application by entering etx_gpio. Now, if you press the button or place the object in front of the IR sensor, then the output LED should be toggled. Please check the below output image. I am placing my hand in front of the IR sensor, then the onboard LED is toggling.

ESP32 GPIO example using NuttX RTOS

This is a very basic example. You can just use this logic and develop any complex application. In our next tutorial, we will implement the I2C communication using the NuttX RTOS and ESP32.

You can also read the below tutorials.

Linux Device Driver TutorialsC Programming Tutorials
FreeRTOS TutorialsNuttX RTOS Tutorials
RTX RTOS TutorialsInterrupts Basics
I2C Protocol – Part 1 (Basics)I2C Protocol – Part 2 (Advanced Topics)
STM32 TutorialsLPC2148 (ARM7) Tutorials
PIC16F877A Tutorials8051 Tutorials
Unit Testing in C TutorialsESP32-IDF Tutorials
Raspberry Pi TutorialsEmbedded Interview Topics
Reset Sequence in ARM Cortex-M4BLE Basics
VIC and NVIC in ARMSPI – Serial Peripheral Interface Protocol
STM32F7 Bootloader TutorialsRaspberry PI Pico Tutorials
STM32F103 Bootloader TutorialsRT-Thread RTOS Tutorials
Zephyr RTOS Tutorials - STM32Zephyr RTOS Tutorials - ESP32
AUTOSAR TutorialsUDS Protocol Tutorials
Product ReviewsSTM32 MikroC Bootloader Tutorial
VHDL Tutorials
Subscribe
Notify of
guest

This site uses Akismet to reduce spam. Learn how your comment data is processed.

0 Comments
Inline Feedbacks
View all comments
Table of Contents