GPIO Linux Device Driver (GPIO Interrupt) – Linux Device Driver Tutorial Part 36

This article is a continuation of the  Series on Linux Device Drivers and carries the discussion on Linux device drivers and their implementation. The aim of this series is to provide easy and practical examples that anyone can understand. This is the GPIO Linux Device Driver (GPIO Interrupt) using Raspberry PI – Linux Device Driver Tutorial Part 36.

In our previous tutorial, we have just used the GPIO pin as an output and we made it high and low. In this tutorial, we will see how to handle the input from GPIO.

We are using the Raspberry PI 4 Model B for this demonstration.

You can also read SysfsProcfsWorkqueueCompletionSoftirq, and threaded IRQ in the Linux device driver.

GPIO Linux Device Driver

Prerequisites

Hardware Required

  • Raspberry Pi
  • Breadboard
  • Resistor
  • LED
  • Push-button (In our tutorial, we have used a vibration sensor as an input device)

Bring up Raspberry PI

  1. Install Raspberry Pi OS (32-bit) with desktop in the SD card.
  2. Then install the kernel header using sudo apt install raspberrypi-kernel-headers

For your information, In my Raspberry PI 4 board, kernel 5.4.51-v7l+ is installed.

Accessing the input GPIO in Linux Kernel

  1. Verify the GPIO is valid or not.
  2. If it is valid, then you can request the GPIO from the Kernel GPIO subsystem.
  3. Set the direction of the GPIO as an input
  4. Set the debounce-interval
  5. Read the GPIO.
  6. You enable IRQ also for edge/level triggered if you need it.
  7. Then release the GPIO while exiting the driver or once you are done.

GPIO APIs in Linux kernel

We have seen almost all the APIs in our last tutorial. So, please go through that. Here we will see the APIs that we have missed in that last tutorial.

Set the debounce-interval

The below API is used for sets debounce time for a GPIO. Right now raspberry pi is not supporting that. That’s why we have commented on that line in our source code. Instead, we used some software hack to eliminate multiple times IRQ being called for a single rising edge transition. You can remove the software hack and uncomment that gpio_set_debounce() if your microcontroller supports this.

int gpiod_set_debounce(unsigned gpio, unsigned debounce);

where,

gpio :  GPIO that you want to set the debounce value.

debounce : Delay of the debounce.

It returns 0 on success. otherwise, <0.

Get the IRQ number for the GPIO

Using the below API, you can get the IRQ number for the specific GPIO.

int gpio_to_irq(unsigned gpio);

where,

gpio :  GPIO that you want to get the IRQ number.

Request the IRQ

Here is where you need to register the GPIO IRQ number and its handler to the Linux Interrupts with the proper interrupt flags. You can find the details regarding requesting the GPIO here. Please note that you have to free the IRQ once you are done with the interrupt.

Interrupt Flags

While registering the GPIO interrupt using request_irq() you can use any one of the flags based on your need.

IRQF_TRIGGER_RISING  
IRQF_TRIGGER_FALLING
IRQF_TRIGGER_HIGH   
IRQF_TRIGGER_LOW

So we are all set. Let’s jump into the programming.

Example Programming

In this example, I have just taken the 2 GPIOs. One is for the input and one is for the output.

  • GPIO 21 – OUTPUT
  • GPIO 25 – INPUT

LED has been connected to the OUTPUT pin (GPIO 21) and the Vibration sensor has been connected to the INPUT pin (GPIO 25). You can connect the push-button also into the INPUT pin.

So the concept is whenever the vibration is detected, it will toggle the LED. Just simple right. Let’s write the code.

Connection Diagram

Driver Source Code

[Get the source code from the GitHub]

/***************************************************************************//**
*  \file       driver.c
*
*  \details    Simple GPIO driver explanation (GPIO Interrupt)
*
*  \author     EmbeTronicX
*
*  \Tested with Linux raspberrypi 5.4.51-v7l+
*
*******************************************************************************/
#include <linux/kernel.h>
#include <linux/init.h>
#include <linux/module.h>
#include <linux/kdev_t.h>
#include <linux/fs.h>
#include <linux/cdev.h>
#include <linux/device.h>
#include <linux/delay.h>
#include <linux/uaccess.h>  //copy_to/from_user()
#include <linux/gpio.h>     //GPIO
#include <linux/interrupt.h>
#include <linux/err.h>
/* Since debounce is not supported in Raspberry pi, I have addded this to disable 
** the false detection (multiple IRQ trigger for one interrupt).
** Many other hardware supports GPIO debounce, I don't want care about this even 
** if this has any overhead. Our intention is to explain the GPIO interrupt.
** If you want to disable this extra coding, you can comment the below macro.
** This has been taken from : https://raspberrypi.stackexchange.com/questions/8544/gpio-interrupt-debounce
**
** If you want to use Hardaware Debounce, then comment this EN_DEBOUNCE.
**
*/
#define EN_DEBOUNCE

#ifdef EN_DEBOUNCE
#include <linux/jiffies.h>

extern unsigned long volatile jiffies;
unsigned long old_jiffie = 0;
#endif

//LED is connected to this GPIO
#define GPIO_21_OUT (21)

//LED is connected to this GPIO
#define GPIO_25_IN  (25)

//GPIO_25_IN value toggle
unsigned int led_toggle = 0; 

//This used for storing the IRQ number for the GPIO
unsigned int GPIO_irqNumber;

//Interrupt handler for GPIO 25. This will be called whenever there is a raising edge detected. 
static irqreturn_t gpio_irq_handler(int irq,void *dev_id) 
{
  static unsigned long flags = 0;
  
#ifdef EN_DEBOUNCE
   unsigned long diff = jiffies - old_jiffie;
   if (diff < 20)
   {
     return IRQ_HANDLED;
   }
  
  old_jiffie = jiffies;
#endif  

  local_irq_save(flags);
  led_toggle = (0x01 ^ led_toggle);                             // toggle the old value
  gpio_set_value(GPIO_21_OUT, led_toggle);                      // toggle the GPIO_21_OUT
  pr_info("Interrupt Occurred : GPIO_21_OUT : %d ",gpio_get_value(GPIO_21_OUT));
  local_irq_restore(flags);
  return IRQ_HANDLED;
}
 
dev_t dev = 0;
static struct class *dev_class;
static struct cdev etx_cdev;
 
static int __init etx_driver_init(void);
static void __exit etx_driver_exit(void);
 
 
/*************** Driver functions **********************/
static int etx_open(struct inode *inode, struct file *file);
static int etx_release(struct inode *inode, struct file *file);
static ssize_t etx_read(struct file *filp, 
                char __user *buf, size_t len,loff_t * off);
static ssize_t etx_write(struct file *filp, 
                const char *buf, size_t len, loff_t * off);
/******************************************************/

//File operation structure 
static struct file_operations fops =
{
  .owner          = THIS_MODULE,
  .read           = etx_read,
  .write          = etx_write,
  .open           = etx_open,
  .release        = etx_release,
};

/*
** This function will be called when we open the Device file
*/ 
static int etx_open(struct inode *inode, struct file *file)
{
  pr_info("Device File Opened...!!!\n");
  return 0;
}

/*
** This function will be called when we close the Device file
*/ 
static int etx_release(struct inode *inode, struct file *file)
{
  pr_info("Device File Closed...!!!\n");
  return 0;
}

/*
** This function will be called when we read the Device file
*/ 
static ssize_t etx_read(struct file *filp, 
                char __user *buf, size_t len, loff_t *off)
{
  uint8_t gpio_state = 0;
  
  //reading GPIO value
  gpio_state = gpio_get_value(GPIO_21_OUT);
  
  //write to user
  len = 1;
  if( copy_to_user(buf, &gpio_state, len) > 0) {
    pr_err("ERROR: Not all the bytes have been copied to user\n");
  }
  
  pr_info("Read function : GPIO_21 = %d \n", gpio_state);
  
  return 0;
}

/*
** This function will be called when we write the Device file
*/
static ssize_t etx_write(struct file *filp, 
                const char __user *buf, size_t len, loff_t *off)
{
  uint8_t rec_buf[10] = {0};
  
  if( copy_from_user( rec_buf, buf, len ) > 0) {
    pr_err("ERROR: Not all the bytes have been copied from user\n");
  }
  
  pr_info("Write Function : GPIO_21 Set = %c\n", rec_buf[0]);
  
  if (rec_buf[0]=='1') {
    //set the GPIO value to HIGH
    gpio_set_value(GPIO_21_OUT, 1);
  } else if (rec_buf[0]=='0') {
    //set the GPIO value to LOW
    gpio_set_value(GPIO_21_OUT, 0);
  } else {
    pr_err("Unknown command : Please provide either 1 or 0 \n");
  }
  
  return len;
}

/*
** Module Init function
*/ 
static int __init etx_driver_init(void)
{
  /*Allocating Major number*/
  if((alloc_chrdev_region(&dev, 0, 1, "etx_Dev")) <0){
    pr_err("Cannot allocate major number\n");
    goto r_unreg;
  }
  pr_info("Major = %d Minor = %d \n",MAJOR(dev), MINOR(dev));

  /*Creating cdev structure*/
  cdev_init(&etx_cdev,&fops);

  /*Adding character device to the system*/
  if((cdev_add(&etx_cdev,dev,1)) < 0){
    pr_err("Cannot add the device to the system\n");
    goto r_del;
  }

  /*Creating struct class*/
  if(IS_ERR(dev_class = class_create(THIS_MODULE,"etx_class"))){
    pr_err("Cannot create the struct class\n");
    goto r_class;
  }

  /*Creating device*/
  if(IS_ERR(device_create(dev_class,NULL,dev,NULL,"etx_device"))){
    pr_err( "Cannot create the Device \n");
    goto r_device;
  }
  
  //Output GPIO configuration
  //Checking the GPIO is valid or not
  if(gpio_is_valid(GPIO_21_OUT) == false){
    pr_err("GPIO %d is not valid\n", GPIO_21_OUT);
    goto r_device;
  }
  
  //Requesting the GPIO
  if(gpio_request(GPIO_21_OUT,"GPIO_21_OUT") < 0){
    pr_err("ERROR: GPIO %d request\n", GPIO_21_OUT);
    goto r_gpio_out;
  }
  
  //configure the GPIO as output
  gpio_direction_output(GPIO_21_OUT, 0);
  
  //Input GPIO configuratioin
  //Checking the GPIO is valid or not
  if(gpio_is_valid(GPIO_25_IN) == false){
    pr_err("GPIO %d is not valid\n", GPIO_25_IN);
    goto r_gpio_in;
  }
  
  //Requesting the GPIO
  if(gpio_request(GPIO_25_IN,"GPIO_25_IN") < 0){
    pr_err("ERROR: GPIO %d request\n", GPIO_25_IN);
    goto r_gpio_in;
  }
  
  //configure the GPIO as input
  gpio_direction_input(GPIO_25_IN);
  
  /*
  ** I have commented the below few lines, as gpio_set_debounce is not supported 
  ** in the Raspberry pi. So we are using EN_DEBOUNCE to handle this in this driver.
  */ 
#ifndef EN_DEBOUNCE
  //Debounce the button with a delay of 200ms
  if(gpio_set_debounce(GPIO_25_IN, 200) < 0){
    pr_err("ERROR: gpio_set_debounce - %d\n", GPIO_25_IN);
    //goto r_gpio_in;
  }
#endif
  
  //Get the IRQ number for our GPIO
  GPIO_irqNumber = gpio_to_irq(GPIO_25_IN);
  pr_info("GPIO_irqNumber = %d\n", GPIO_irqNumber);
  
  if (request_irq(GPIO_irqNumber,             //IRQ number
                  (void *)gpio_irq_handler,   //IRQ handler
                  IRQF_TRIGGER_RISING,        //Handler will be called in raising edge
                  "etx_device",               //used to identify the device name using this IRQ
                  NULL)) {                    //device id for shared IRQ
    pr_err("my_device: cannot register IRQ ");
    goto r_gpio_in;
  }
  
  
 
  pr_info("Device Driver Insert...Done!!!\n");
  return 0;

r_gpio_in:
  gpio_free(GPIO_25_IN);
r_gpio_out:
  gpio_free(GPIO_21_OUT);
r_device:
  device_destroy(dev_class,dev);
r_class:
  class_destroy(dev_class);
r_del:
  cdev_del(&etx_cdev);
r_unreg:
  unregister_chrdev_region(dev,1);
  
  return -1;
}

/*
** Module exit function
*/
static void __exit etx_driver_exit(void)
{
  free_irq(GPIO_irqNumber,NULL);
  gpio_free(GPIO_25_IN);
  gpio_free(GPIO_21_OUT);
  device_destroy(dev_class,dev);
  class_destroy(dev_class);
  cdev_del(&etx_cdev);
  unregister_chrdev_region(dev, 1);
  pr_info("Device Driver Remove...Done!!\n");
}
 
module_init(etx_driver_init);
module_exit(etx_driver_exit);
 
MODULE_LICENSE("GPL");
MODULE_AUTHOR("EmbeTronicX <[email protected]>");
MODULE_DESCRIPTION("A simple device driver - GPIO Driver (GPIO Interrupt) ");
MODULE_VERSION("1.33");

Makefile

obj-m += driver.o
 
KDIR = /lib/modules/$(shell uname -r)/build
 
 
all:
    make -C $(KDIR)  M=$(shell pwd) modules
 
clean:
    make -C $(KDIR)  M=$(shell pwd) clean

Testing the Device Driver

  • Build the driver by using Makefile (sudo make)
  • Load the driver using sudo insmod driver.ko
  • Just press the button or vibrate the vibration sensor.
  • That output LED should be toggled.

Output Video

Click here if you don’t see the output gif

GPIO Linux Device Driver using Raspberry Pi

In our next tutorial, we will see the I2C and its subsystem in the Linux Device Driver.

Please find the other Linux device driver tutorials here.

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.

8 Comments
Oldest
Newest Most Voted
Inline Feedbacks
View all comments
Table of Contents