Ping Sonar Python code

Hello all,

I’m fairly new to coding in Python and ran into an issue. I’m using this code: ping-python/simplePingExample.py at master · bluerobotics/ping-python · GitHub except instead of myPing.get_distance() I changed it to myPing.get_distance_simple(). The issue I am running into is that the sonar is giving the distance values every 4 seconds instead of instantaneously or every second. Do you know what I can do to resolve this issue?

Thank you for your help!

#!/usr/bin/env python

#simplePingExample.py
from brping import Ping1D
import time
import argparse

from builtins import input

##Parse Command line options
############################

parser = argparse.ArgumentParser(description="Ping python library example.")
parser.add_argument('--device', action="store", required=True, type=str, help="Ping device port.")
parser.add_argument('--baudrate', action="store", type=int, default=115200, help="Ping device baudrate.")
args = parser.parse_args()

#Make a new Ping
myPing = Ping1D(args.device, args.baudrate)
if myPing.initialize() is False:
    print("Failed to initialize Ping!")
    exit(1)

print("------------------------------------")
print("Starting Ping..")
print("Press CTRL+C to exit")
print("------------------------------------")

input("Press Enter to continue...")

# Read and print distance measurements with confidence
while True:
    data = myPing.get_distance_simple()
    if data:
        print("Distance: %s\tConfidence: %s%%" % (data["distance"], data["confidence"]))
    else:
        print("Failed to get distance data")

Hello,

What version of the python package are you using? We recommend to get the 0.0.7.

How are you testing it? What is the environment like?

Hello,

Thank you for your response. I double checked and it is 0.0.7 package. It is being tested by having it connected to the raspberry pi. We are currently testing in air, but the same results were received when tested in water. Any other suggestions?

Are you using a Bluart or the Raspberry PI hardware serial?

Are you using the default firmware communicating at 115200 baud?

You code runs fine here, but I don’t have a Pi Zero I could test it on. Can you check the cpu usage while it is running?

Hello again. I have done some tests here. I believe the source of the issue is the cpu usage of this example. Try adding a time.sleep(0.1) at the last line, like this:

#simplePingExample.py
from brping import Ping1D
import time
import argparse

from builtins import input

##Parse Command line options
############################

parser = argparse.ArgumentParser(description="Ping python library example.")
parser.add_argument('--device', action="store", required=True, type=str, help="Ping device port.")
parser.add_argument('--baudrate', action="store", type=int, default=115200, help="Ping device baudrate.")
args = parser.parse_args()

#Make a new Ping
myPing = Ping1D(args.device, args.baudrate)
if myPing.initialize() is False:
    print("Failed to initialize Ping!")
    exit(1)

print("------------------------------------")
print("Starting Ping..")
print("Press CTRL+C to exit")
print("------------------------------------")

input("Press Enter to continue...")

# Read and print distance measurements with confidence
while True:
    data = myPing.get_distance_simple()
    if data:
        print("Distance: %s\tConfidence: %s%%" % (data["distance"], data["confidence"]))
    else:
        print("Failed to get distance data")
    time.sleep(0.1)

Note that with this, the theoretical maximum frequency you will get will be 10 Hz. One would think that removing the sleep would make things faster, but that will increase cpu usage so much that it can get worse instead. You can decrease that number, but not remove it.

Hello, I am running the code as you say here, however, there seems to be a lag in the measurements?

For example, I can lift the vehicle out of the water, but with the sounder still in the water, and it takes the sensor some time to catch up.

Is there some kind of filtering happening that I can turn off?

I’m trying to do an altitude hold controller so I can follow the sea floor contours, but due to the lag I am getting a lot of oscillation.

Note, I’m am hooked directly into the RPi, I’m not using the USB adapter.

Thanks!

Hello Mike,

What is your version of the ping-python library? 0.0.8 has some improvements to reduce CPU usage.

Also try decreasing the time.sleep(0.1) to 0.01 as some data is possibly being stored in the serial buffer.

Hello, I am working with Mike on this. Our ping-python lirary is version 0.0.8, as you suggest. We actually already had it at time.sleep(.01). I tried changing it to .001, with no noticeable effect on the lag. The measurements still lag about one second.

Any other suggestions?

Hello,

Do you mind sharing your code? Are you running it in the Pi Zero too?

We are running it on the Rasperry Pi Model B–the one that comes with the Blue ROV 2. We were running code wrapped in ROS python, but then I switched to just the example code to make sure that it wasn’t ROS causing the issue. Still encountered the same problem. Here is our code:

#test example code to troubleshoot ping data lag
from brping import Ping1D
import time
import argparse

##Parse Command line options
############################

parser = argparse.ArgumentParser(description="Ping python library example.")
parser.add_argument('--device', action="store", required=True, type=str, help="Ping device port.")
parser.add_argument('--baudrate', action="store", type=int, default=115200, help="Ping device baudrate.")
args = parser.parse_args()

#Make a new Ping
myPing = Ping1D(args.device, args.baudrate)
if myPing.initialize() is False:
    print("Failed to initialize Ping!")
    exit(1)

print("Starting Ping..")

# Read and print altitude + confidence
while True:
    data = myPing.get_distance_simple()
    if data:
        print("Distance: %s\tConfidence: %s%%" % (data["distance"], data["confidence"]))
    else:
        print("Failed to get distance data")
    time.sleep(0.01)

The only thing that might be different is the port when we run it. I am running it from the command line with:

python test_altimeter_python_code.py --device /dev/ttyAMA0

This port is because we have it plugged in directly into the UART chip on the pi. Python version is 2.7

Hello, I also emailed support about this issue, and they pointed me to the forums. It occurs to me that this may be a different issue than the original one above, so I made a separate forum post here to continue the discussion:

I collated everything we have tried there.