Multiple HC-SR04 with Arduino using interrupts

When using autonomous vehicles, it’s important to be able to detect obstacles fast and efficient. The ideal way to do this, is by using Lidar, but that may turn out expensive. A much cheaper way is by using multiple ultrasonic sensors like the HC-SR04. This tutorial explains how you can use multiple HC-SR04, reading and sending data all at once with an Arduino microcontroller.

Autonomous vehicles, HC-SR04 sensors

Step 1: Detecting objects with HC-SR04
Step 2: Multiple HC-SR04 with Arduino using interrupts
Step 2b: Multiple HC-SR04 with Arduino using only 1 interrupt pin
Step 3: Choosing the right vehicle
Step 4: Automatic steer correction with HC-SR04
Step 5a: Vehicle accessories – SSD1306 status display
Step 5b: Vehicle accessories – Rotary encoder illuminated button
Step 6: Autonomous vehicles, putting it all together
Alternative 1: Steer correction with HC-SR04: Single sensor, stop and scan
Alternative 2: Steer correction with HC-SR04: Servo controlled car

The HC-SR04

A tutorial about the HC-SR04, and how it can be used in an Arduino, can be found in a previous article here.

Many sensors, 1 Arduino

For this tutorial, the Arduino Uno will be used with 2 sensors. Once the method is understood, it can be easily up-scaled to, for example, an Arduino Micro with 5 sensors, as shown in the image below (prototype).

Multiple HC-SR04
Multiple HC-SR04

The reason the Arduino Uno was chosen, is because it appears to be the most used one for prototyping, and up-scaling is basically just copy-paste.

1 trigger, many echos

All sensors will have their trigger pin connected to each other so they can be triggered by just 1 pin on the Arduino. From here on, we will refer to this pin as the “common trigger”.

Triggering all sensors with the same pin means they will al start measuring at the same moment. It also means that they will start replying about roughly the same moment, and need to be monitored all at once.
In this tutorial, you will learn how to do this using interrupts.

The echo pin of every sensor, will be connected to a separate interrupt pin on the Arduino board (not just any pin). Since the Arduino Uno has only 2 interrupt pins, only 2 sensors can be used. The Arduino Micro has 5 interrupt pins, and thus can read 5 sensors. The method remains the same, so up-scaling (or down-scaling) is very easy.

Arduino Uno with 2x HC-SR04 on interrupt pins
Arduino Uno with 2x HC-SR04 on interrupt pins
Arduino Uno with 2x HC-SR04 on interrupt pins schematics

Download the electrical schematic for the Arduino Uno with two HC-SR04 sensors on interrupt pins below.

More HC-SR04 sensors

As you may have guessed, the maximum number of sensors that can be used with this method depends on the number of interrupt pins. On most Arduino boards, that number is rather limited.

To be able to use more sensor with this method, you can either

  1. Go for the 32 bit Arduinos like the ZERO or the DUE, which have interrupts on (almost) all pins, or the MKR series which have 10 interrupts pins.
  2. Choose a different method by polling with micros() and using registers to read the pin states, rather than using digitalRead().
    HOWEVER, the interrupt method seems to be the most reliable way to do this. This tutorial won’t cover the alternative methods.

The drawback

The downside off this method is that when you place the sensors next to each other (in 1 line), they may interfere with each other’s signal. Remember the 15° angle they can operate in?

15° angle interference
15° angle interference

So only use this method if the sensors are placed in such a way they cannot interfere with one another (like a pentagon) .

Pentagon setup with 5x HC-SR04
Pentagon setup with 5x HC-SR04

Finding the interrupt pins

Browsing through some datasheets and schematics, you can find that the Arduino Uno – which uses the ATmeage328 / ATmega168 microcontroller – has 2 interrupt pins; INT0 and INT1

  • PD2 which is pin 2 on the Uno board, is the interrupt 0 (INT0) pin
  • PD3 which is pin 3 on the Uno board, is the interrupt 1 (INT1) pin
Arduino Uno INT pins
Arduino Uno INT pins

If you want to know more about interrupts on the Arduino, you can find more information on the Arduino reference page.

The Arduino Uno code

#define tINT 2            // Total number of interrupts
#define triggerPin 4      // Pin number for the common trigger
#define pingDelay 50      // How many milliseconds between each measurement ; keep > 5ms
#define debugDelay 200    // How many milliseconds between each Serial.print ; keep > 200ms
#define soundSpeed 343.0  // Speed of sound in m/s

volatile unsigned long travelTime[tINT];  // Place to store traveltime of the pusle
volatile unsigned long startTime[tINT];   // Place to store ping times (interrupt)
float distance[tINT];                     // Calculated distances in cm
unsigned long lastPollMillis;
unsigned long lastDebugMillis;

/****************************************************************
      SETUP
****************************************************************/
void setup()
{
  Serial.begin(115200);
  while (!Serial) {
    ; // Wait for Serial
  }
  Serial.println("--- Serial monitor started ---");
  pinMode(triggerPin, OUTPUT);   // Set common triggerpin as output

  // Manage interrupt pins here
  pinMode(2, INPUT);    // Set interrupt pin 2 (INT0) as INPUT (sensor 1)
  pinMode(3, INPUT);    // Set interrupt pin 3 (INT1) as INPUT (sensor 2)
  attachInterrupt(0, call_INT0, CHANGE );   // ISR for INT0
  attachInterrupt(1, call_INT1, CHANGE );   // ISR for INT1
  // END

  lastPollMillis = millis();
  lastDebugMillis = millis();
}

/****************************************************************
      LOOP
****************************************************************/
void loop()
{
  // Poll every x ms
  if (millis() - lastPollMillis >= pingDelay)
  {
    doMeasurement();
    lastPollMillis = millis();
  }

  // Print every y ms (comment out in production)
  if (millis() - lastDebugMillis >= debugDelay)
  {
    for (int i = 0; i < tINT; i++) {
      Serial.print(distance[i]);
      Serial.print(" - ");
    }
    Serial.println();
    lastDebugMillis = millis();
  }
}

/****************************************************************
      Retrieve measurement and set next trigger
****************************************************************/
void doMeasurement()
{
  // First read will be 0 (no distance  calculated yet)

  // Read the previous result (pause interrupts while doing so)
  noInterrupts();   // cli()
  for (int i = 0; i < tINT; i++)
  {
    distance[i] = travelTime[i] / 2.0 * (float)soundSpeed / 10000.0;   // in cm
  }
  interrupts();   // sei();

  // Initiate next trigger
  // digitalWrite(triggerPin, LOW);  // rest of loop already takes > 2µs
  // delayMicroseconds(2);
  digitalWrite(triggerPin, HIGH);    // HIGH pulse for at least 10µs
  delayMicroseconds(10);
  digitalWrite(triggerPin, LOW);     // Set LOW again
}

/****************************************************************
      INTERRUPT handling
****************************************************************/
// INTerrupt 0 (pin 2 on Uno)
void call_INT0()
{
  byte pinRead;
  // pinRead = digitalRead(2);      // Slower ; Read pin 2
  pinRead = PIND >> 2 & B00000001;  // Faster ; Read pin 2/PD2
  interruptHandler(pinRead, 0);
}

// INTerrupt 1 (pin 3 on Uno)
void call_INT1()
{
  byte pinRead;
  // pinRead = digitalRead(3);      // Slower ; Read pin 3
  pinRead = PIND >> 3 & B00000001;  // Faster ; Read pin 3/PD3
  interruptHandler(pinRead, 1);
}

// Common function for interrupts
void interruptHandler(bool pinState, int nIRQ)
{
  unsigned long currentTime = micros();  // Get current time (in µs)
  if (pinState)
  {
    // If pin state has changed to HIGH -> remember start time (in µs)
    startTime[nIRQ] = currentTime;
  }
  else
  {
    // If pin state has changed to LOW -> calculate time passed (in µs)
    travelTime[nIRQ] = currentTime - startTime[nIRQ];
  }
}
// END

As you can see on the timing diagram, 1 trigger pulse is sent and both sensors will start responding roughly on the same time. Thanks to the interrupt method, a very accurate measurement is achieved and this way data is received in a fast, reliable and accurate way.

Timing diagram 2 sensors
Timing diagram for left and right sensors

Arduino Micro

Up-scaling to 5 sensors to the Arduino Micro is quite easy.
4 steps are required

  1. Define new number of total interrupts
  2. Define extra input pins (echo)
  3. Attach extra interrupts
  4. Update/Add extra functions for the interrupt calls

Step 1

#define tINT 5            // Total number of interrupts

Step 2

  pinMode(3, INPUT);    // Set interrupt pin 3 (INT0) as INPUT (sensor 1)
  pinMode(2, INPUT);    // Set interrupt pin 2 (INT1) as INPUT (sensor 2)
  pinMode(7, INPUT);    // Set interrupt pin 7 (INT6) as INPUT (sensor 3)
  pinMode(0, INPUT);    // Set interrupt pin 0 (INT2) as INPUT (sensor 4) !! is also RX pin !!
  pinMode(1, INPUT);    // Set interrupt pin 1 (INT3) as INPUT (sensor 5) !! is also TX pin !!

Step 3

  attachInterrupt(0, call_INT0, CHANGE );   // ISR for INT0
  attachInterrupt(1, call_INT1, CHANGE );   // ISR for INT1
  attachInterrupt(4, call_INT6, CHANGE );   // ISR for INT6, but call with INT4 (!?)
  attachInterrupt(2, call_INT2, CHANGE );   // ISR for INT2
  attachInterrupt(3, call_INT3, CHANGE );   // ISR for INT3

Step 4

/****************************************************************
      INTERRUPT handling
****************************************************************/

// INTerrupt 0 (pin 3 on Micro)
void call_INT0()
{
  byte pinRead;
  // pinRead = digitalRead(3);    // Slower ; Read pin 3
  pinRead = PIND  & B0001;        // Faster ; Read pin 3/PD0
  interruptHandler(pinRead, 0);
}


// INTerrupt 1 (pin 2 on Micro)
void call_INT1()
{
  byte pinRead;
  // pinRead = digitalRead(2);    // Slower ; Read pin 2
  pinRead = PIND >> 1 & B0001;    // Faster ; Read pin 2/PD1
  interruptHandler(pinRead, 1);
}

// INTerrupt 2 (pin 0 on Micro)
void call_INT2()
{
  byte pinRead;
  // pinRead = digitalRead(0);    // Slower ; Read pin 0
  pinRead = PIND >> 2 & B0001;    // Faster ; Read pin 0/PD2
  interruptHandler(pinRead, 2);
}

// INTerrupt 3 (pin 1 on Micro)
void call_INT3()
{
  byte pinRead;
  // pinRead = digitalRead(1);    // Slower ; Read pin 1
  pinRead = PIND >> 3 & B0001;    // Faster ; Read pin 1/PD3
  interruptHandler(pinRead, 3);
}

// INTerrupt 6 (pin 7 on Micro)
void call_INT6()
{
  byte pinRead;
  // pinRead = digitalRead(7);      // Slower ; Read pin 7
  pinRead = PINE >> 6 & B00000001;  // Faster ; Read pin 7/PE6
  interruptHandler(pinRead, 4);
}

Timing diagram with 5 sensors

Again, with 1 trigger, all sensors start at roughly the same moment in time, and can be read all at once which makes this method very suitable for detecting objects with autonomous vehicles.

Timing diagram 5 sensors
Timing diagram for 5 sensors

Conclusion

Although this is the fastest and most accurate way to handle multiple sensors (keeping in mind their positions relative to each other), the biggest disadvantage is that for each sensor, a separate interrupt pin is required.


References
Arduino Boards: Arduino Uno R3 – Arduino Nano V3 – Arduino Micro
Arduino Software: Arduino IDE
Arduino Playground: Library NewPing
Arduino forum: Arduino Micro Interrupts 6
Arduino Reference: Port RegistersattachInterrupt()interrupt()noInterrrupt()pulseIn()pulseInLong()Servo library
Random Nerd Tutorials: Complete Guide for Ultrasonic Sensor HC-SR04 with Arduin
Circuit Digest: Arduino Interrupts Tutorial
Electro Noobs: Arduino register control, timers and interruptions
Wikipedia: Speed of sound – Echolocation