Ping1D lag in receiving measurements

We have a ping installed on our new AUV we are building. We are getting considerable lag - about 2 seconds, which makes altitude control using the ping impossible.

This lag can be seen in these two plots. It was taken in a flat bottom pool. The depth sensor reaches its maximum 2s (at t=146s) before the ping reaches its minimum (at t=148s).

On our previous version of this vehicle, the altitude controller worked fine in the tank. When we upgraded the vehicle, we replaced the CPU and downloaded the latest ping python software. From then onwards we noticed the lag issues. We have tried downgrading the ping python software to 0.0.10 (what we used in the initial trials), but the lag issue still exists.

The ping firmware is currently 3.26. Sample rate = 10Hz.

Do you know how to fix these lag issues?

If a new version of the firmware fixes these issues, is there a way to update the ping firmware remotely (without using ping-viewer)?

Are you running Ping connected directly in the pixhawk or in companion ?
Ping does a series of fitting and filters to get the best result from the samples and some delay is expected but I can’t confirm phase delay right now.

We currently have a navio2 in our system (it isn’t a bluerov), but we are connected directly to its UART port.

A small delay would be fine, but 2 seconds is a lot.

How are you communicating with it ?
Can you share the code ? It may be a buffer problem.

Here’s the ROS node I’m using to communicate with the ping. It wouldn’t let me upload the file, so here it is pasted in:

#!/usr/bin/env python3

from brping import Ping1D
import rospy
from sensor_msgs.msg import Range
import numpy as np
import floatpi.srv
import std_srvs.srv

class Altimeter:
    def __init__(self):
        device = rospy.get_param("~device", "/dev/ttyAMA0")
        baudrate = rospy.get_param("~baudrate", 115200)
        sample_rate = rospy.get_param("~sample_rate", 10.0)
        speed_of_sound = rospy.get_param("~speed_of_sound", 1500.0)  # 1500m/s is the speed of sound in salt water, 1435 for fresh, 343 for air

        self.auto_mode = rospy.get_param("~auto_mode", True)
        self.range_min = rospy.get_param("~range_min", 0.1)
        self.range_max = rospy.get_param("~range_max", 30.0)

        self.range_pub = rospy.Publisher('ping', Range, queue_size=1)

        self.field_of_view = 30 * np.pi / 180.0

        # Old initialisation...
        # self.pinger = Ping1D(device, baudrate)

        # New initialisation
        self.pinger = Ping1D()
        self.pinger.connect_serial(device, baudrate)

        if self.pinger.initialize() is False:
            rospy.logerr("Failed to initialize Ping")
            exit(1)

        self.pinger.set_speed_of_sound(int(speed_of_sound))

        if not self.auto_mode:
            self.pinger.set_mode_auto(0)
            scan_length = (self.range_max - self.range_min) *1000.0
            self.pinger.set_range(self.range_min*1000., scan_length)
            rospy.loginfo("Setting scan range to [%f, %f] (m)" %self.range_min, self.range_max)

        self.count = 0

        self.set_range_service = rospy.Service('set_pinger_range', floatpi.srv.SetPingerRange, self.setRangeCallback)
        self.set_mode_service = rospy.Service('set_pinger_mode', std_srvs.srv.SetBool, self.setModeCallback)
        print("Started services")
        rospy.Timer(rospy.Duration(1 / sample_rate), self.timerCallback)

    def setRangeCallback(self, req):
        self.range_min = req.range_min
        self.range_max = req.range_max
        self.pinger.set_mode_auto(0)
        scan_length = (self.range_max - self.range_min) * 1000.0
        self.pinger.set_range(int(self.range_min * 1000.), int(scan_length))
        rospy.loginfo("Setting pinger to auto mode - necessary for custom scan range")
        rospy.loginfo("Setting scan range to [%f, %f] (m)" % (self.range_min, self.range_max))
        res = floatpi.srv.SetPingerRangeResponse()
        res.success = True
        return res

    def setModeCallback(self, req):
        self.pinger.set_mode_auto(req.data)
        if req.data is True:
            mode = "Auto"
        else:
            mode = "Manual"
        res = std_srvs.srv.SetBoolResponse()
        res.success = True
        res.message = "Set mode to %s" % mode
        rospy.loginfo("Set pinger mode to %s" % mode)
        return res



    def timerCallback(self, event):
        data = self.pinger.get_distance()

        if data:
            range_msg = Range()
            range_msg.header.stamp = rospy.Time.now()
            range_msg.header.frame_id = 'pinger'
            range_msg.header.seq = self.count
            range_msg.field_of_view = self.field_of_view
            range_msg.min_range = 0.5
            range_msg.max_range = 30.0
            range_msg.range = float(data["distance"])/1000.0
            self.range_pub.publish(range_msg)
        else:
            rospy.loginfo("Failed to get distance data")
        self.count += 1


if __name__ == "__main__":
    rospy.init_node('pinger')
    alt = Altimeter()
    rospy.spin()

This lag issue is really holding up our development, is there any updates/possible solutions?

Hi Jackson,

Sorry for the delay! Have you tested our minimal example ?
I just tested it here and everything appears to be normal, I was unable to detect the 2s delay that you found.
If everything goes fine with the example, I would recommend to run some kind of python profile in your code to detect where is slowing things, or check the cpu usage to see if something is holding the processing down.

Hi Patrick,
Sorry for the delay, it takes quite a long time to set up the tests for this.
Yes I have tested the minimal example, I built the code attached around that example. The CPU usage is fine, barely anything is running.

To show you the problem, I have adapted your simple example for the ping, and added the depth sensor.

#!/usr/bin/env python

#simplePingExample.py
from brping import Ping1D
import time
import argparse
import ms5837
from builtins import input
import csv
import os
##Parse Command line options
############################

parser = argparse.ArgumentParser(description="Ping python library example.")
parser.add_argument('--device', action="store", required=False, type=str, help="Ping device port. E.g: /dev/ttyUSB0")
parser.add_argument('--baudrate', action="store", type=int, default=115200, help="Ping device baudrate. E.g: 115200")
parser.add_argument('--udp', action="store", required=False, type=str, help="Ping UDP server. E.g: 192.168.2.2:9090")
args = parser.parse_args()
if args.device is None and args.udp is None:
    parser.print_help()
    exit(1)

# Make a new Ping
#myPing = Ping1D()
#if args.device is not None:
#    myPing.connect_serial(args.device, args.baudrate)
#elif args.udp is not None:
#    (host, port) = args.udp.split(':')
#    myPing.connect_udp(host, int(port))

myPing = Ping1D(args.device, args.baudrate)

if myPing.initialize() is False:
    print("Failed to initialize Ping!")
    exit(1)

sensor = ms5837.MS5837_30BA()
# We must initialize the sensor before reading it
if not sensor.init():
   print("Sensor could not be initialized")
   exit(1)
# We have to read values from sensor to update pressure and temperature
if not sensor.read():
    print("Sensor read failed!")
    exit(1)

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

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

with open('logs.csv', 'w') as f:
    writer = csv.writer(f)
    writer.writerow(["Time", "Depth", "Range"])

# Read and print distance measurements with confidence
while True:
    data = myPing.get_distance()
    if sensor.read():
        depth = sensor.depth()
        print("Depth: %f"%depth)
    else:
        print("Failed to get depth")
    alt = float(data["distance"])/1000.0
    if data:
        print("Distance: %s\tConfidence: %s%%" % (alt, data["confidence"]))
    else:
        print("Failed to get distance data")

    with open('logs.csv', 'a') as f:
        writer = csv.writer(f)
        writer.writerow([time.time(), depth, alt])

    time.sleep(0.1)

I dunked the AUV in the tank.

The results show a lag between the peaks of the depth, and the troughs of the ping.

I have updated the ping to the latest firmware, but I am still getting these issues.

I am only allowed one image per post. I repeated the dunking of the AUV, and this time recorded the values using ROS. It shows similar results, a clear lag between the peaks of the depth and troughs of the ping.

Hi guys! Up this thread!
Is this time lag normal for altimeter because of firmware filters, algorithms ant others?
My fw version 3.28

Hi @hells1ng, welcome to the forum :slight_smile:

The sensor (profile) measurements don’t have a built in delay, but the target tracking algorithm (which determines the “distance estimate”) uses a low pass filter that takes into account some number of previous profiles. The actual algorithm is closed source and I don’t have access to it, but from some testing with Ping Viewer it seems like it might be using uniformly weighted averaging over about 20 pings, regardless of the ping rate.

Assuming that’s correct, a ping rate of 1 per second (1 Hz) would mean an instant transition from one flat level to another would result in a delay in the distance estimate of ~20 seconds (during which it is gradually catching up). Normally the sample rate is significantly faster than that, and at a 20 Hz ping rate the distance estimate for the same transition would catch up after ~1 second.

Note that the maximum ping rate is determined from the slowest of

  • the user set ping_interval
  • the combination of profiling range (automatic by default, or user set in manual mode) and user set speed of sound (i.e. you can’t scan faster than physically possible - each ping needs to be measured before the next one can be transmitted)

It’s also worth noting that there are limitations on how fast you can receive updates, determined by

  • communication (baud) rate (e.g. 9600 bits/second or 115200 bits/second)
  • the messages being sent (e.g. distance_simple is smaller (and accordingly a bit faster to send) than distance, which is quite a bit smaller than profile)

which will also add some small amount of delay. Receiving updates less frequently than the ping interval shouldn’t increase the tracking estimate delay.

Note also that the low pass nature of the built in tracking algorithm helps to smooth the output if the signal is noisy (e.g. from coral or rocks on the surface being measured, or fish swimming in front of the sensor), and since ping rates are generally quite fast relative to the motion of a vehicle it’s unlikely to be particularly problematic. That said, there is a tradeoff there that implicitly assumes data with that level of smoothing is likely to be more accurate in the conditions the sensor is expected to be used in, and if that’s not the case for your use-case then it may be better to read the profile directly and do your own distance estimates (either real-time or in post processing).

One example where that may be relevant is if you have say a fast-moving vehicle going over large stacked blocks, where short transition times at sharp height changes may be more relevant and important than the risk of false/jumpy readings from noisy data. @jshields’s original application of altitude control is another one where lower-confidence readings with a faster response are potentially desirable, particularly if the flight controller is already doing its own smoothing, and/or using a Kalman filter or similar to determine data trustworthiness.

1 Like