Distance measurement with ultrasonic sensor Parallax PING))) (C++)

This tutorial guides you through wiring a Parallax PING))) ultrasonic sensor to a Raspberry Pi. A distance to an object can then be measured by a run-time measurement.

Before starting you should read What is a ROS Wrapper?, Write a ROS Wrapper (C++) and Package and Test Your Driver.

In this project, an ultrasonic sensor module (Parallax PING)))) is put into operation. The working principle of an Parallax PING))) is explained. It is also described how a measurement with ultrasound works and on which essential factors it depends. For the commissioning of the sensor, we take a Raspberry Pi as an example.

What is ultrasonic?

Ultrasound is a high-pitched sound wave whose frequency exceeds the audible range of human hearing.

https://lastminuteengineers.b-cdn.net/wp-content/uploads/arduino/Ultrasonic-Frequency-Range-Spectrum.png

Humans can hear sound waves that vibrate in the range of about 20 times a second (a deep rumbling noise) to 20,000 times a second (a high-pitched whistle). However, ultrasound has a frequency of more than 20,000 Hz and is therefore inaudible to humans.

What is an ultrasonic sensor?

An ultrasonic sensor is generally a sensor that determines the distance to an object via a run-time measurement. It cannot classify which object is located at this distance. As shown in the following figure, the ultrasonic sensor emits ultrasonic waves. This is where it gets its name. At an object, these ultrasonic waves are reflected and reflected back. A membrane on the sensor receives these ultrasonic waves. Since it is known how fast the carrier medium is, a distance to the object is determined based on the time interval between sending and receiving the ultrasonic waves. We will take a closer look at what this means in concrete terms below.

https://raw.githubusercontent.com/Michdo93/test2/main/ultraschall.PNG

The Parallax PING))) sensor

An Parallax PING))) ultrasonic distance sensor actually consists of two ultrasonic transducers. Ultrasonic transducers and ultrasonic sensors are devices that generate or sense ultrasound energy. They can be divided into three broad categories: transmitters, receivers and transceivers. Transmitters convert electrical signals into ultrasound, receivers convert ultrasound into electrical signals, and transceivers can both transmit and receive ultrasound.

The Parallax PING))) sensor looks like this:

https://raw.githubusercontent.com/Michdo93/test2/main/parallax_ping_sensor.jpg

The Parallax PING))) uses a transceivers in comparison to the HC-SR04. We know the trigger of the HC-SR04. This is what we call a transmitter. And the receiver called echo. At the Parallax PING))) we call the transceiver signal.

Once this acts as a transmitter that converts the electrical signal into 40 KHz ultrasonic sound pulses and once this acts as a receiver and listens for the transmitted pulses. When the "receiver" receives these pulses, it produces an output pulse whose width is proportional to the distance of the object in front.

This sensor provides excellent non-contact range detection between 3 cm to 300 cm (~11 feet) with an accuracy of 1-2 mm.

Since it operates on 5 volts, it can be connected directly to a Raspberry Pi or any other 5V logic microcontroller.

Technical Specifications

Operating Voltage

DC 5V

Operating Current

35mA

Operating Frequency

40KHz

Max Range

3m

Min Range

3cm

Ranging Accuracy

1-2mm

Measuring Angle

20 degree

Trigger Input Signal

10µS TTL pulse

Dimension

46 x 22 x 16mm

Pinout

Let’s take a look at its pinout.

https://raw.githubusercontent.com/Michdo93/test2/main/parallax_ping_sensor.jpg

5V supplies power to the Parallax PING))) ultrasonic sensor. You can connect it to one of the 5V outputs from your Raspberry Pi.

Sig (Signal) pin is used to trigger ultrasonic sound pulses. By setting this pin to HIGH for 10µs, the sensor initiates an ultrasonic burst. Also it works as an Echo pin which goes high when the ultrasonic burst is transmitted and remains high until the sensor receives an echo, after which it goes low. So after triggering you have to set the Pin to low that it can get high by receiving the echo. By measuring the time the Echo pin stays high, the distance can be calculated.

GND is the ground pin. Connect it to the ground of your Raspberry Pi.

Operating principle

It all starts when the signal pin is set HIGH for 10µs. In response, the sensor transmits an ultrasonic burst of eight pulses at 40 kHz. This 8-pulse pattern is specially designed so that the receiver can distinguish the transmitted pulses from ambient ultrasonic noise.

These eight ultrasonic pulses travel through the air away from the transmitter. Meanwhile the signal pin goes HIGH to initiate the echo-back signal.

If those pulses are not reflected back, the echo signal times out and goes low after 38ms (38 milliseconds). Thus a pulse of 38ms indicates no obstruction within the range of the sensor.

https://raw.githubusercontent.com/Michdo93/test2/main/HC-SR04-Ultrasonic-Sensor-Working-Echo-when-no-Obstacle.gif

If those pulses are reflected back, the signal pin goes low as soon as the signal is received. This generates a pulse on the signal pin whose width varies from 150 µs to 25 ms depending on the time taken to receive the signal.

https://raw.githubusercontent.com/Michdo93/test2/main/HC-SR04-Ultrasonic-Sensor-Working-Echo-reflected-from-Obstacle.gif

Calculating the distance

The width of the received pulse is used to calculate the distance from the reflected object. This can be worked out using the simple distance-speed-time equation we learned in high school. An easy way to remember the equation is to put the letters in a triangle.

https://lastminuteengineers.b-cdn.net/wp-content/uploads/arduino/Distance-Speed-Time-Formula-Triangle.png

Let us take an example to make it more clear. Suppose we have an object in front of the sensor at an unknown distance and we receive a pulse of 500µs width on the echo pin. Now let’s calculate how far the object is from the sensor. For this we will use the below equation.

Distance = Speed x Time

Here we have the value of time i.e. 500 µs and we know the speed. Of course it’s the speed of sound! It is 340 m/s. To calculate the distance we need to convert the speed of sound into cm/µs. It is 0.034 cm/μs. With that information we can now calculate the distance!

Distance = 0.034 cm/µs x 500 µs

But we’re not done yet! Remember that the echo pulse indicates the time it takes for the signal to be sent and reflected back. So to get the distance, you have to divide your result by two.

Distance = (0.034 cm/µs x 500 µs) / 2
Distance = 8.5 cm

Now we know that the object is 8.5 cm away from the sensor.

Wiring it to the Raspberry Pi

For this example, I took the Raspberry Pi because it not only allows us to cleverly connect various sensors and actuators for our tutorials, but also because ROS can be installed on the Raspberry Pi. I could also connect the sensors and actuators to an Arduino, but would need accordingly a computer on which ROS is installed, which connects serially with the Arduino. The same applies to similar microcontrollers.

Please have a look on this:

https://raw.githubusercontent.com/Michdo93/test2/main/rpi.png

There are 3 pins on the ultrasonic module which are connected to the Raspberry:

Sensor pin

Raspberry Pi pin

5V

Pin 2 (VCC)

GND

Pin 6 (GND)

Sig

Pin 11 (GPIO17)

https://raw.githubusercontent.com/Michdo93/test2/main/parallax_ping.png

That's enough. As we can see from the data sheet, the signal is never above 3.3V. This makes the Parallax Ping much easier to use than the HC-SR04 if you want to use a Raspberry Pi. So we save a voltage divider and corresponding resistors.

Preparations on the Raspberry Pi

We need to make sure that we can use the GPIO pins. GPIO stands for General Purpose Input Output. A GPIO is a general purpose digital contact pin on an integrated circuit (IC) whose behavior, whether as an input or output contact, can be freely determined by logic programming. GPIO contacts are not given a purpose, so they are unassigned by default. Specifically, this means that we can use a GPIO pin either as input or as output. We can also do both alternately one after the other. This is left to our programming.

First we need to update the packages and paths.

First we need to update the packages and paths.

sudo apt-get update
sudo apt-get upgrade

We can install the WiringPi library with

sudo apt-get install wiringpi

Programming the distance measurement

We now create our C++ script:

#include <iostream>
#include <wiringPi.h>
#include "libParallaxPING.h"

ParallaxPING::ParallaxPING(){}

void ParallaxPING::init(int signal)
{
    this->signal = signal;
    this->timeout = 0.05;
}

double ParallaxPING::distance()
{
    arrivalTime = 0;
    startTime = 0;

    // set to low
    pinMode(signal, OUTPUT);
    digitalWrite(signal, LOW);
    delay(500);

    delay(10);

    // set to high
    digitalWrite(signal, HIGH);
    delayMicroseconds(10);

    // set to low
    digitalWrite(signal, LOW);

    // set to input
    digitalWrite(signal, INPUT)

    timeout_start = micros();

    // Count microseconds that SIG was high
    while(digitalRead(signal) == 0) {
        startTime = micros();

        if(startTime - timeout_start > timeout) {
            return -1;
        }
    }

    while(digitalRead(signal) == 0) {
        arrivalTime = micros();

        if(startTime - timeout_start > timeout) {
            return -1;
        }
    }

    if(startTime != 0 && arrivalTime != 0) {
        pulse_duration = arrivalTime - startTime;
        distance = 100*((pulse_duration/1000000.0)*340.29)/2;

        if(distance >= 0) {
            return distance;
        } else {
            return -1;
        }
    } else {
        return -1;
    }
}

Then we need a header file:

#ifndef DEF_SONAR
#define DEF_SONAR

class ParallaxPING
{
  public:
    ParallaxPING();
    void init(int signal);
    double distance();

  private:
    int signal;
    volatile long arrivalTime;
    volatile long startTime;
    long timeout_start;
    long timeout;
    long pulse_duration;
    double distance;
};

#endif

And at least we can test it with following code:

#include <iostream>
#include <wiringPi.h>
#include "libParallaxPING.h"

using namespace std;

int signal = 0;

int main()
{
    if (wiringPiSetup() == -1)
        return -1;

    ParallaxPING ultrasonic;
    ultrasonic.init(signal);

    while(1){
        cout << "Speed is " << ultrasonic.distance() << " m/s." << endl;
    }
}

This will now measure the distance every second until the script is aborted using CTRL+C.

Wait a minute, why does the trigger suddenly use the 1 and not the 18 and why do we now have to use the 5 for the echo and not the 24? This is due to WiringPi, as the following illustration explains:

https://raw.githubusercontent.com/Michdo93/test2/main/WiringPi.PNG

We have learned how to handle the GPIO pins to send an output once and receive an input once. The output refers to the TRIG pin of the sensor. The trigger signal is an ultrasonic wave that the sensor emits. For the returned echo we use the ECHO pin of the sensor, which we connect to the Raspberry Pi via voltage divider. This GPIO pin now refers to the input. Since we know the speed of sound (carrier medium), we determine an elapsed time between the start time when we release the trigger and the arrival time when the echo comes back. This is called run-time measurement.

In the next chapter, we'll look at Speed measurement with ultrasonic sensor Parallax PING))) (C++).

Wiki: Drivers/Tutorials/DistanceMeasurementWithUltrasonicSensorParallaxPINGCpp (last edited 2022-11-14 14:36:26 by Michdo93)