Hilti-Research / hilti-slam-challenge-2021

73 stars 6 forks source link

Possible framedrops #10

Closed GustavHager closed 2 years ago

GustavHager commented 2 years ago

Hi

I tried extracting the data from the uzh_tracking_area_run2.bag, but could not get the timestamps/sequence numbering to make sense.

I used the rosbag python api to extract each message from the bagfile, but it seems like a few of the images for each camera is missing, and that this happens periodically. I would expect this to be easily handled using the sequence-numbers of each message in the message-header (since it should skip an image). However this is not the case, as each the number always increments by one.

For the first 100 images for camera0 and camera1, the timestamps as integer nanoseconds looks like this, with cam0 plotted as a blue line, and cam1 as a dashed red-line. (that is it is two lines in the plot, at more or less the same spot, so the dropped frames are at least happening at the same time approximately for both cameras)

cam_ts.pdf If the difference between each sample was constant this should be a straight line, possibly with some wobbles.

There seems to be a similar behavior for the IMU-timestamps as well, where there is sudden jumps in the delay at around 200-samples, but i did not look as closely at this since it is getting late.

I have only checked this one bagfile so far, but i will get back when i have investigated the remainder, but this might be a few days.

bedaberner commented 2 years ago

Hi Gustav I tried to reproduce the issues you mentioned but did not manage to do so. When i graph the timestamp over sequence, i indeed get the straight line you expected even if i take the time of arrival the line is still fairly straight: the same is true for the imu data.

You can check out the code i used to create those graphs below.

#! /usr/bin/python2
import rosbag
from tqdm import tqdm
import sys
import matplotlib.pyplot as plt

if __name__ == "__main__":

    # check if files where provided in the command line argument
    if len(sys.argv) > 1:
        input = sys.argv[1]
    else:
        input = '/home/beda/Phasma/raw_datasets_corrected/uzh_tracking_area_run2.bag'

    cam0_sequence = []
    cam0_sequence_orig = -1
    cam0_time = []
    cam0_toa = []

    cam1_sequence = []
    cam1_sequence_orig = -1
    cam1_time = []
    cam1_toa = []

    imu_sequence = []
    imu_sequence_orig = -1
    imu_time = []
    imu_toa = []

    msg_nr = 0

    input_bag = rosbag.Bag(input)
    for topic, msg, t in tqdm(
            input_bag.read_messages(['/alphasense/cam0/image_raw', '/alphasense/cam1/image_raw', '/alphasense/imu']),
            total=input_bag.get_message_count(
                    topic_filters=['/alphasense/cam0/image_raw', '/alphasense/cam1/image_raw', '/alphasense/imu'])):

        if topic == '/alphasense/cam0/image_raw':
            if cam0_sequence_orig == -1:
                cam0_sequence_orig = msg.header.seq
            cam0_time.append(msg.header.stamp.to_nsec())
            cam0_toa.append(t.to_nsec())
            cam0_sequence.append(msg.header.seq - cam0_sequence_orig)
        if topic == '/alphasense/cam1/image_raw':
            if cam1_sequence_orig == -1:
                cam1_sequence_orig = msg.header.seq
            cam1_time.append(msg.header.stamp.to_nsec())
            cam1_toa.append(t.to_nsec())
            cam1_sequence.append(msg.header.seq - cam1_sequence_orig)
            msg_nr += 1
        if topic == '/alphasense/imu':
            if imu_sequence_orig == -1:
                imu_sequence_orig = msg.header.seq
            imu_time.append(msg.header.stamp.to_nsec())

            imu_sequence.append(msg.header.seq - imu_sequence_orig)
        if msg_nr >= 100:
            break

fig, ax = plt.subplots()
ax.plot(cam0_sequence, cam0_time, c="black")
ax.plot(cam1_sequence, cam1_time, "--", c="r")

ax.set(xlabel='sequence (manipulated to start at 0)', ylabel='timestamp [ns]', title="timestamps cams")
plt.legend(["cam0", "cam1"])
ax.grid()
fig.savefig("timestamps.png", dpi=400)

fig2, ax2 = plt.subplots()
ax2.plot(imu_sequence, imu_time)

ax2.set(xlabel='sequence (manipulated to start at 0)', ylabel='timestamp [ns]', title="timestamps imu")
plt.legend(["imu"])
ax2.grid()
fig2.savefig("timestamps_imu.png", dpi=400)

fig3, ax3 = plt.subplots()
ax3.plot(cam0_sequence, cam0_toa, c="black")
ax3.plot(cam1_sequence, cam1_toa, "--", c="r")

ax3.set(xlabel='sequence (manipulated to start at 0)', ylabel='time of arrival [ns]', title="time of arrival cams")
plt.legend(["cam0", "cam1"])
ax3.grid()
fig3.savefig("time_of_arrival.png", dpi=400)
GustavHager commented 2 years ago

Hi Thanks for the quick answer and the example code.

It looks like i had a issue with numerical precision in the conversion from ros-timestamps to an integer-nanoseconds representation causing the issue. In hindsight i should have been more careful with pythons insistence on defaulting to doubles in inappropriate places.