If you haven’t read the previous tutorial on multiple sensors, you may want to read that one first: Multiple HC-SR04 with Arduino using interrupts
With using multiple interrupts, there’s the disadvantage that the sensors may interfere with each other, when facing the same direction, and crossing each others line of sight. Also, since most Arduino boards are limited on the number of interrupt pins, the use of multiple sensors could become a problem.
In this tutorial, a slightly different approach is taken that requires only 1 interrupt pin, and offering the use of as many sensors as there are I/O pins available, without the sensors interfering with each others signal.
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
One echo, multiple triggers
Opposite with the previous method (1 trigger, multiple echos), this method uses only 1 echo pin (in stead of multiple), and multiple trigger pins (in stead of one). This gives the advantage of requiring only 1 interrupt pin.
Wiring it up
A minor disadvantage of linking all the senors’ echo pins together, is that they disrupt one another. This is very simply fixed with the use of a diode, as shown in the schematic below.

The above can be extended very simply by just adding more sensors with every sensor connected to a different trigger pin, and with the echo pin connected via a diode to the common echo pin.

Concept of program
The concept of the program is fairly simple:
- Trigger sensor 1
- Wait for the reply on the echo pin and store the result
- Trigger sensor 2
- Wait for the reply on the echo pin and store the result
- Trigger sensor 3
- Wait for the reply on the echo pin and store the result
- …
Which basically gives a result, similar to the diagram below. Since you control the triggers, you know when data arrives on the echo pin, which sensor it was that sent the reply.

As you may have already notice, you’ll see that with many sensors and long distances, this can be a quite time-consuming method, and may not be very ideal for situations where this measurement is very time critical.
The timing diagrams below show the same setup where the object is in close range, and the total time for the measurement takes only about 4.4 milliseconds, and a bit further away, the total time takes up to almost 44 milliseconds, already 10 times longer.
Doubling the amount of sensors, will also (more than) double the amount of time to measure.


Source code
Very similar to the previous method, the echo pin is assigned to an interrupt pin, and the trigger pin(s) is configured as a normal output pin.
#define tSENS 4 // Total number of sensors #define echoPin 2 // Pin to collect echo signal --> This must be any interrupt pin // #define triggerPins[tSENS] {3,4}; // Trigger pin for each sensor #define pingDelay 50 // How many milliseconds between each measurement (ping) ; best to keep > 5ms #define soundSpeed 343.0 // Speed of sound in m/s (343m/s at 20°C with dry air) volatile unsigned long startEcho; // Place to store start time (interrupt) volatile unsigned long stopEcho; // Place to store stop time (interrupt) float distancesCm[tSENS]; // Distances in cm // Place pin numbers of the sensors' triggers here int triggerPins[tSENS] = {4, 5, 6, 7}; // Trigger pin for each sensor // Poll timer unsigned long lastPingMillis; /**************************************************************** SETUP ****************************************************************/ void setup() { Serial.begin(115200); while (!Serial) { ; // Wait for Serial } Serial.println("--- Serial monitor started ---"); // Set all trigger pins as OUTPUTS for (int i = 0; i < tSENS; i++) { pinMode(triggerPins[i], OUTPUT); // Set trigger pin x as OUTPUT } // Set echo pin pinMode(echoPin, INPUT); // Set echo pin as INPUT (do not use pullup when using diodes !) attachInterrupt(0, ISR_ECHO, CHANGE ); // Set interrupt call for echo pin lastPingMillis = millis(); } /**************************************************************** LOOP ****************************************************************/ void loop() { // Ping every x ms if (millis() - lastPingMillis >= pingDelay) { doMeasurement(); // Call measure procedure Serial.println(String(distancesCm[0]) + " - " + String(distancesCm[1]) + " - " + String(distancesCm[2]) + " - " + String(distancesCm[3])); lastPingMillis = millis(); } } /**************************************************************** Retrieve measurement and set next trigger ****************************************************************/ void doMeasurement() { // First read will be bad (or 0) unsigned long startWait; unsigned long timeout = 50; // 50ms is the max amount of time we'll wait (23ms = 4m = out of range) // For each sensor for (int s = 0; s < tSENS; s++) { startEcho = 0; // Reset start stopEcho = 0; // Reset stop time // Initiate next trigger // digitalWrite(triggerPins[s], LOW); // rest of loop already takes > 2µs // delayMicroseconds(2); digitalWrite(triggerPins[s], HIGH); // HIGH pulse for at least 10µs delayMicroseconds(10); digitalWrite(triggerPins[s], LOW); // Set LOW again startWait = millis(); // remember time we started to wait for the echo signal while (startEcho == 0 or stopEcho == 0) { // Keep looping unill start and stoptime is not 0 OR a timeout occurs if (startWait + timeout < millis()) { // This will result in a distance of 0 startEcho = 0; stopEcho = 0; break; // exit the while loop } } noInterrupts(); // cli() distancesCm[s] = (stopEcho - startEcho) * (float)soundSpeed / 1000.0 / 10.0 / 2.0; // in cm interrupts(); // sei(); } } /**************************************************************** INTERRUPT handling (keep as fast(=short) as possible) ****************************************************************/ void ISR_ECHO() { // For ATmega328(P) chips, INT0 as at pin PD2 byte pinRead = PIND >> 2 & B0001; // Read state of interrupt pin if (pinRead) { // State = HIGH -> Remember start time startEcho = micros(); } else { // State is LOW -> Remember stop time stopEcho = micros(); } } //END
Conclusion
Using multiple HC-SR04 sensors with multiple triggers and a common echo, has the advantage that all Arduino boards can be used while still using the interrupt method. The reading may be a bit slower, since all sensors will measure one by one, but for most applications it’s still fast enough.
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 Registers – attachInterrupt() – 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