diff --git a/perception_dataset/utils/misc.py b/perception_dataset/utils/misc.py index 029b9459..a38bb304 100644 --- a/perception_dataset/utils/misc.py +++ b/perception_dataset/utils/misc.py @@ -56,6 +56,8 @@ def get_lidar_camera_synced_frame_info( for lidar_index, lidar_timestamp in enumerate(lidar_timestamp_list): if lidar_index >= num_load_frames: break + if current_image_index >= len(image_timestamp_list): + break image_timestamp = image_timestamp_list[current_image_index] while image_timestamp - lidar_timestamp < lidar_to_camera_latency_sec - ( diff --git a/tests/utils/test_misc.py b/tests/utils/test_misc.py index c378a7a3..edd5abef 100644 --- a/tests/utils/test_misc.py +++ b/tests/utils/test_misc.py @@ -164,3 +164,22 @@ def test_get_lidar_camera_synced_frame_info_num_load_frames(): num_load_frames=num_load_frames, ) assert_synced_frame_info_list(expected, synced_frame_info_list) + + +def test_get_lidar_camera_synced_frame_info_too_large_num_load_frames(): + # Test case where len(lidar_timestamp_list) >= num_load_frames > len(image_timestamp_list) + image_timestamp_list = [0.552, 0.652] + lidar_timestamp_list = [0.4, 0.499, 0.6] + + expected = [[0, 0, None], [1, 1, None]] + num_load_frames = 3 + + synced_frame_info_list = misc_utils.get_lidar_camera_synced_frame_info( + image_timestamp_list=image_timestamp_list, + lidar_timestamp_list=lidar_timestamp_list, + lidar_to_camera_latency_sec=0.162, + system_scan_period_sec=0.1, + max_camera_jitter_sec=0.03, + num_load_frames=num_load_frames, + ) + assert_synced_frame_info_list(expected, synced_frame_info_list)