From 13ea8e8b8a4951fb630dbc9108666995c8443bf6 Mon Sep 17 00:00:00 2001 From: Kai Wong Date: Tue, 11 Jan 2022 15:01:22 -0800 Subject: [PATCH] Bug fixes and doc tweaks for fw 2.2 release * Fix issues with new pcap port guessing logic * Bump versions for release --- CHANGELOG.rst | 6 +- CMakeLists.txt | 2 +- README.rst | 1 - ouster_client/CMakeLists.txt | 2 +- python/README.rst | 6 +- python/docs/conf.py | 4 +- python/docs/devel.rst | 24 ++- python/docs/examples.rst | 2 +- python/docs/quickstart.rst | 1 + python/setup.py | 2 +- python/src/ouster/pcap/pcap.py | 69 +++---- python/tests/conftest.py | 40 +++- python/tests/test_pcap.py | 344 +++++++++++++++++++-------------- 13 files changed, 294 insertions(+), 209 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 4484a3ef..00278477 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -3,9 +3,11 @@ Changelog ========= -[unreleased] +[20220107] ============ +* add support for arm64 macos and linux. Releases are now built and tested on these platforms +* add support for Python 3.10 * update supported vcpkg tag to 2021.05.12 * add preliminary cpack and install support. It should be possible to use a pre-built SDK package instead of including the SDK in the build tree of your project @@ -73,7 +75,7 @@ ouster_viz python ------ -* update ouster-sdk version to 0.3.0b3 +* update ouster-sdk version to 0.3.0 * improve heuristics for identifying sensor data in pcaps, including new packet formats * release builds for wheels on Windows now use the VS 2017 toolchain and runtime (previously 2019) * fix potential use-after-free in ``LidarScan.fields`` diff --git a/CMakeLists.txt b/CMakeLists.txt index 9dd10319..a5674fac 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -4,7 +4,7 @@ list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake) include(DefaultBuildType) # ==== Project Name ==== -project(ouster_example VERSION 20210608) +project(ouster_example VERSION 20220107) # ==== Options ==== option(CMAKE_POSITION_INDEPENDENT_CODE "Build position independent code." ON) diff --git a/README.rst b/README.rst index da5a9480..33ff582f 100644 --- a/README.rst +++ b/README.rst @@ -146,7 +146,6 @@ Keyboard controls: ``p`` Increase point size ``o`` Decrease point size ``m`` Cycle point cloud coloring mode - ``v`` Toggle range cycling ``b`` Cycle top 2D image ``n`` Cycle bottom 2D image ``shift + r`` Reset camera diff --git a/ouster_client/CMakeLists.txt b/ouster_client/CMakeLists.txt index 41df58d9..8a385474 100644 --- a/ouster_client/CMakeLists.txt +++ b/ouster_client/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.1.0) # ==== Project Name ==== project(ouster_client VERSION 0.3.0) -set(ouster_client_VERSION_SUFFIX "b3") +set(ouster_client_VERSION_SUFFIX "") # ==== Requirements ==== find_package(Eigen3 REQUIRED) diff --git a/python/README.rst b/python/README.rst index d06689b2..1e06fe3c 100644 --- a/python/README.rst +++ b/python/README.rst @@ -25,13 +25,13 @@ Pre-built binaries are provided on `PyPI`_ for the following platforms: - Most glibc-based Linux distributions on x86_64 and ARM64 platforms (``manylinux2010_x86_64``, ``manylinux2014_aarch64``) - macOS >= 10.13 on x86_64 platforms (``macosx_10_13_x86_64``) -- macOS >= 11.0 on Apple M1 for Python >= 3.8(``macosx_11_0_arm64``) +- macOS >= 11.0 on Apple M1 for Python >= 3.8 (``macosx_11_0_arm64``) - Windows 10 on x86_64 platforms (``win_amd64``) Building from source is supported on: -- Ubuntu 18.04, 20.04, and Debian 10 (x86-64, AArch64) -- macOS >= 10.13 (x86-64) +- Ubuntu 18.04, 20.04, and Debian 10 (x86-64, aarch64) +- macOS >= 10.13 (x86-64), >= 11.0 (arm64) - Windows 10 (x86-64) .. _PyPI: https://pypi.org/project/ouster-sdk/ diff --git a/python/docs/conf.py b/python/docs/conf.py index a48fb966..7c26c4dc 100644 --- a/python/docs/conf.py +++ b/python/docs/conf.py @@ -25,7 +25,7 @@ # The full version, including alpha/beta/rc tags version = '0.3' -release = '0.3.0b1' +release = '0.3.0' # -- General configuration --------------------------------------------------- @@ -120,7 +120,7 @@ # napoleon_use_param = False # ----- Todos Configs ------ -todo_include_todos = True +todo_include_todos = False todo_link_only = True todo_emit_warnings = True diff --git a/python/docs/devel.rst b/python/docs/devel.rst index 924d7214..522a96a8 100644 --- a/python/docs/devel.rst +++ b/python/docs/devel.rst @@ -14,6 +14,8 @@ Building the Python SDK from source requires several dependencies: - `jsoncpp `_ >= 1.7 - `libtins `_ >= 3.4 - `libpcap `_ +- `libglfw3 `_ >= 3.2 +- `libglew `_ >= 2.1 - `Python `_ >= 3.6 (with headers and development libraries) - `pybind11 `_ >= 2.0 @@ -42,6 +44,9 @@ After you have the system dependencies, you can build the SDK with: # first, specify the path to the ouster_example repository $ export OUSTER_SDK_PATH= + # make sure you have an up-to-date version of pip installed + $ python3 -m pip install --user --upgrade pip + # then, build an installable "wheel" package $ python3 -m pip wheel --no-deps $OUSTER_SDK_PATH/python @@ -64,16 +69,16 @@ The currently tested vcpkg tag is ``2021.05.12``. After that, using a developer .. code:: powershell # first, specify the path to the ouster_example repository - PS > $env:OUSTER_SDK_PATH= + PS > $env:OUSTER_SDK_PATH="" - # point cmake to the location of vcpkg - PS > $env:CMAKE_TOOLCHAIN_FILE=/scripts/buildsystems/vcpkg.cmake + # point cmake to the location of vcpkg (make sure to use an absolute path) + PS > $env:CMAKE_TOOLCHAIN_FILE="\scripts\buildsystems\vcpkg.cmake" # then, build an installable "wheel" package - PS > py -m pip wheel --no-deps $env:OUSTER_SDK_PATH\python + PS > py -m pip wheel --no-deps "$env:OUSTER_SDK_PATH\python" # or just install directly (virtualenv recommended) - PS > py -m pip install $env:OUSTER_SDK_PATH\python + PS > py -m pip install "$env:OUSTER_SDK_PATH\python" See the top-level README in the `Ouster Example repository`_ for more details on setting up a development environment on Windows. @@ -81,6 +86,7 @@ development environment on Windows. .. _vcpkg: https://github.com/microsoft/vcpkg/blob/master/README.md .. _Ouster Example repository: https://github.com/ouster-lidar/ouster_example + Developing ========== @@ -95,11 +101,11 @@ The Ouster SDK package includes configuration for ``flake8`` and ``mypy``. To ru # install and run flake8 linter $ python3 -m pip install flake8 $ cd ${OUSTER_SDK_PATH}/python - $ flake8 + $ python3 -m flake8 # install and run mypy in an environment with $ python3 -m pip install mypy - $ mypy src/ + $ python3 -m mypy src/ Running Tests @@ -111,14 +117,14 @@ SDK package: .. code:: console $ cd ${OUSTER_SDK_PATH}/python - $ pytest + $ python3 -m pytest To run tests against multiple Python versions simultaneously, use the ``tox`` package: .. code:: console $ cd ${OUSTER_SDK_PATH}/python - $ tox + $ python3 -m tox This will take longer, since it will build the package from a source distribution for each supported Python version available. diff --git a/python/docs/examples.rst b/python/docs/examples.rst index 19f0b61d..77d31ba7 100644 --- a/python/docs/examples.rst +++ b/python/docs/examples.rst @@ -546,7 +546,7 @@ The visualizer can be controlled with mouse and keyboard: .. include:: ../../README.rst :start-line: 136 - :end-line: 167 + :end-line: 169 To run the visualizer with a sensor: diff --git a/python/docs/quickstart.rst b/python/docs/quickstart.rst index 21d2c890..2824b1e1 100644 --- a/python/docs/quickstart.rst +++ b/python/docs/quickstart.rst @@ -187,6 +187,7 @@ Just like with the sample data, you can create a :py:class:`.PacketSource` from .. code:: python >>> source = client.Sensor(hostname) + >>> info = source.metadata Now we have a ``source`` from our sensor! To visualize data from your sensor, proceed to `Visualizing Lidar Data`_ directly below. diff --git a/python/setup.py b/python/setup.py index 4abbcf3b..108a93dd 100644 --- a/python/setup.py +++ b/python/setup.py @@ -119,7 +119,7 @@ def run(self): setup( name='ouster-sdk', url='https://github.com/ouster-lidar/ouster_example', - version='0.3.0b3', + version='0.3.0', package_dir={'': 'src'}, packages=find_namespace_packages(where='src'), namespace_packages=['ouster'], diff --git a/python/src/ouster/pcap/pcap.py b/python/src/ouster/pcap/pcap.py index 75d087d9..5e0280c4 100644 --- a/python/src/ouster/pcap/pcap.py +++ b/python/src/ouster/pcap/pcap.py @@ -33,6 +33,7 @@ class _UDPStreamInfo: class _stream_info: """Gather some useful info about UDP data in a pcap.""" + def __init__(self, infos: Iterable[_pcap.packet_info]) -> None: self.total_packets = 0 self.encapsulation_protocol = set() @@ -60,51 +61,53 @@ def _guess_ports(udp_streams: Dict[_UDPStreamKey, _UDPStreamInfo], """Find possible UDP sources matching the metadata. The current approach is roughly: 1) treat each unique source / destination - port and IP as a single logical 'stream' of data. 2) filter out streams that - don't match the expected destination ports and packet sizes specified in the - metadata. 3) produce pairs of lidar/imu streams that have matching source - IPs, or None if a corresponding stream can't be found. + port and IP as a single logical 'stream' of data, 2) filter out streams that + don't match the expected packet sizes specified by the metadata, 3) pair up + any potential lidar/imu streams that appear to be coming from the same + sensor (have matching source IPs) 4) and finally, filter out the pairs that + contradict any ports specified in the metadata. Returns: List of dst port pairs that probably contain lidar/imu data. Duplicate entries are possible and indicate packets from distinct sources. """ - # yapf: disable - # ports are zero if not specified (e.g. in older metadata) - def filter_keys(size: int, dst_port: int) -> Set[Optional[_UDPStreamKey]]: - return {k for k, v in udp_streams.items() - if (size in v.payload_size) - and (not dst_port or k.dst_port == dst_port)} + # allow lone streams when there's no matching data from the same ip + lidar_keys: Set[Optional[_UDPStreamKey]] = {None} + imu_keys: Set[Optional[_UDPStreamKey]] = {None} - # find all lidar and imu 'streams' that match metadata + # find all lidar and imu 'streams' that match expected packet sizes pf = _client.PacketFormat.from_info(info) - lidar_keys = filter_keys(pf.lidar_packet_size, info.udp_port_lidar) - imu_keys = filter_keys(pf.imu_packet_size, info.udp_port_imu) + ss = udp_streams.items() + lidar_keys |= {k for k, v in ss if pf.lidar_packet_size in v.payload_size} + imu_keys |= {k for k, v in ss if pf.imu_packet_size in v.payload_size} # find all src ips for candidate streams lidar_src_ips = {k.src_ip for k in lidar_keys if k} imu_src_ips = {k.src_ip for k in imu_keys if k} - # allow lone streams when there's no matching data from the same ip - lidar_keys.add(None) - imu_keys.add(None) - - # full join on matching src ip to produce distinct lidar/imu stream choices - keys = [(kl, ki) for kl in lidar_keys for ki in imu_keys - if (not kl and ki and ki.src_ip not in lidar_src_ips) - or (kl and not ki and kl.src_ip not in imu_src_ips) - or (kl and ki and kl.src_ip == ki.src_ip)] - # yapf: enable + # yapf: disable + # "full outer join" on src_ip to produce lidar/imu streams from one source + keys = [(klidar, kimu) for klidar in lidar_keys for kimu in imu_keys + if (klidar and kimu and klidar.src_ip == kimu.src_ip) + or (not klidar and kimu and kimu.src_ip not in lidar_src_ips) + or (klidar and not kimu and klidar.src_ip not in imu_src_ips)] # map down to just dst port pairs, with 0 meaning none found - ports = [(kl.dst_port if kl else 0, ki.dst_port if ki else 0) - for (kl, ki) in keys] + ports = [(klidar.dst_port if klidar else 0, kimu.dst_port if kimu else 0) + for (klidar, kimu) in keys] + + # filter out candidates that don't match specified ports + lidar_spec, imu_spec = info.udp_port_lidar, info.udp_port_imu + guesses = [(plidar, pimu) for plidar, pimu in ports + if (plidar == lidar_spec or lidar_spec == 0 or plidar == 0) + and (pimu == imu_spec or imu_spec == 0 or pimu == 0)] + # yapf: enable # sort sensor ports to prefer both found > just lidar > just imu - ports.sort(reverse=True, key=lambda p: (p[0] != 0, p[1] != 0, p)) + guesses.sort(reverse=True, key=lambda p: (p[0] != 0, p[1] != 0, p)) - return ports + return guesses def _packet_info_stream(path: str) -> Iterator[_pcap.packet_info]: @@ -147,8 +150,7 @@ def __init__(self, When not specified, ports are guessed by sampling some packets and looking for the expected packet size based on the sensor metadata. If packets that might be valid sensor data appear on multiple ports, one is - chosen arbitrarily. See ``_guess_streams`` for details. on the - heuristics. + chosen arbitrarily. See ``_guess_ports`` for details. on the heuristics. Packets with the selected destination port that clearly don't match the metadata (e.g. wrong size or init_id) will be silently ignored. @@ -178,13 +180,12 @@ def __init__(self, stats = _stream_info(islice(_packet_info_stream(pcap_path), n_packets)) self._guesses = _guess_ports(stats.udp_streams, self._metadata) - # if ports were inferred, they must be equal or more specific + # fill in unspecified (0) ports with inferred values if len(self._guesses) > 0: lidar_guess, imu_guess = self._guesses[0] - assert lidar_port == lidar_guess or lidar_port <= 0 - assert imu_port == imu_guess or imu_port <= 0 - self._metadata.udp_port_lidar = lidar_guess - self._metadata.udp_port_imu = imu_guess + # guess != port only if port == 0 or guess == 0 + self._metadata.udp_port_lidar = lidar_guess or lidar_port + self._metadata.udp_port_imu = imu_guess or imu_port self._rate = rate self._handle = _pcap.replay_initialize(pcap_path) diff --git a/python/tests/conftest.py b/python/tests/conftest.py index 1ca2d9cd..951ccd5e 100644 --- a/python/tests/conftest.py +++ b/python/tests/conftest.py @@ -1,5 +1,6 @@ from contextlib import closing from os import path +from typing import Iterator import pytest @@ -42,20 +43,41 @@ def meta(base_name: str): @pytest.fixture -def packet(base_name: str, meta: client.SensorInfo) -> client.LidarPacket: - pcap_path = path.join(DATA_DIR, f"{base_name}.pcap") - with closing(pcap.Pcap(pcap_path, meta)) as source: - for p in source: +def meta_2_0(): + meta_path = path.join(DATA_DIR, f"{TESTS['legacy-2.0']}.json") + with open(meta_path, 'r') as f: + return client.SensorInfo(f.read()) + + +@pytest.fixture +def real_pcap_path(base_name: str, meta: client.SensorInfo) -> str: + return path.join(DATA_DIR, f"{base_name}.pcap") + + +@pytest.fixture +def real_pcap(real_pcap_path: str, + meta: client.SensorInfo) -> Iterator[pcap.Pcap]: + pcap_obj = pcap.Pcap(real_pcap_path, meta) + yield pcap_obj + pcap_obj.close() + + +@pytest.fixture +def packet(real_pcap_path: str, meta: client.SensorInfo) -> client.LidarPacket: + # note: don't want to depend on the pcap fixture, since this consumes the + # iterator and it can be shared + with closing(pcap.Pcap(real_pcap_path, meta)) as real_pcap: + for p in real_pcap: if isinstance(p, client.LidarPacket): return p - raise RuntimeError("Failed to find lidar packet in text fixture") + raise RuntimeError("Failed to find lidar packet in test fixture") @pytest.fixture -def packets(base_name: str, meta: client.SensorInfo) -> client.PacketSource: - pcap_path = path.join(DATA_DIR, f"{base_name}.pcap") - with closing(pcap.Pcap(pcap_path, meta)) as source: - ps = list(source) +def packets(real_pcap_path: str, + meta: client.SensorInfo) -> client.PacketSource: + with closing(pcap.Pcap(real_pcap_path, meta)) as real_pcap: + ps = list(real_pcap) return client.Packets(ps, meta) diff --git a/python/tests/test_pcap.py b/python/tests/test_pcap.py index 8a21edce..76a07d2e 100644 --- a/python/tests/test_pcap.py +++ b/python/tests/test_pcap.py @@ -1,10 +1,10 @@ from collections import defaultdict -import os +from copy import copy +from os import path from random import getrandbits, shuffle, random -from typing import Dict, Iterable, Iterator, List -from itertools import chain, islice +from typing import (Dict, Iterable, Iterator, List) +from itertools import chain -from more_itertools import roundrobin import pytest import time @@ -13,49 +13,33 @@ from ouster import client from ouster.client import _client -DATA_DIR = os.path.join(os.path.dirname(os.path.abspath(__file__)), "data") - -NO_RANDOM_TIME = 0 -RANDOM_FLOAT = 1 SLL_PROTO = 42 ETH_PROTO = 1 UDP_PROTO = 17 -# Seed the start timestamp -current_timestamp = time.time() -def random_lidar_packets(metadata, - random_time=NO_RANDOM_TIME - ) -> Iterator[client.LidarPacket]: - global current_timestamp +def fake_packets(metadata: client.SensorInfo, + n_lidar: int = 0, + n_imu: int = 0, + timestamped: bool = False) -> Iterator[client.Packet]: pf = _client.PacketFormat.from_info(metadata) + current_ts = time.time() - timestamp = None - current_timestamp += random() * 4.0 - if random_time == RANDOM_FLOAT: - timestamp = current_timestamp - - while True: - buf = bytearray(getrandbits(8) for _ in range(pf.lidar_packet_size)) - yield client.LidarPacket(buf, metadata, timestamp) - - -def random_imu_packets(metadata, - random_time=NO_RANDOM_TIME - ) -> Iterator[client.ImuPacket]: - global current_timestamp - - pf = _client.PacketFormat.from_info(metadata) + choices = [True] * n_lidar + [False] * n_imu + shuffle(choices) - timestamp = None - current_timestamp += random() * 4.0 - if random_time == RANDOM_FLOAT: - timestamp = current_timestamp + for is_lidar in choices: + current_ts += random() + packet_ts = current_ts if timestamped else None - while True: - buf = bytearray(getrandbits(8) for _ in range(pf.imu_packet_size)) - yield client.ImuPacket(buf, metadata, timestamp) + if is_lidar: + buf = bytearray( + getrandbits(8) for _ in range(pf.lidar_packet_size)) + yield client.LidarPacket(buf, metadata, packet_ts) + else: + buf = bytearray(getrandbits(8) for _ in range(pf.imu_packet_size)) + yield client.ImuPacket(buf, metadata, packet_ts) @pytest.fixture @@ -63,51 +47,113 @@ def n_packets() -> int: return 10 +@pytest.fixture +def lidar_imu_frac() -> float: + return 0.5 + + @pytest.fixture def use_sll() -> int: return False @pytest.fixture -def pcap_path(meta, n_packets, use_sll, tmpdir) -> Iterable[str]: - file_path = os.path.join(tmpdir, "pcap_test.pcap") +def fake_meta(meta_2_0: client.SensorInfo) -> client.SensorInfo: + """Use fw 2.0 metadata for randomly generated packets.""" + return meta_2_0 - packets: Iterable[client.Packet] = islice( - roundrobin(random_lidar_packets(meta), random_imu_packets(meta)), - n_packets) +@pytest.fixture +def fake_pcap_path(lidar_imu_frac: float, fake_meta: client.SensorInfo, + n_packets: int, use_sll: bool, tmpdir: str) -> str: + file_path = path.join(tmpdir, "pcap_test.pcap") + n_lidar = int(lidar_imu_frac * n_packets) + n_imu = n_packets - n_lidar + packets = fake_packets(fake_meta, n_lidar, n_imu) pcap.record(packets, file_path, use_sll_encapsulation=use_sll) - yield file_path + return file_path @pytest.fixture -def pcap_obj(meta, pcap_path) -> Iterable[pcap.Pcap]: - pc = pcap.Pcap(pcap_path, meta) +def fake_pcap(fake_meta, fake_pcap_path) -> Iterable[pcap.Pcap]: + pc = pcap.Pcap(fake_pcap_path, fake_meta) yield pc pc.close() -@pytest.mark.parametrize('test_key', ['legacy-2.0']) @pytest.mark.parametrize('n_packets', [0]) -def test_pcap_read_empty(meta, pcap_path) -> None: - """Check reading with fully specified ports doesn't fail.""" - pcap_obj = pcap.Pcap(pcap_path, meta) - assert pcap_obj.ports == (0, 0) - assert list(pcap_obj) == [] +def test_pcap_read_empty(fake_meta, fake_pcap_path) -> None: + """Check reading an empty pcap doesn't fail.""" + fake_pcap = pcap.Pcap(fake_pcap_path, fake_meta) + assert fake_pcap.ports == (0, 0) + assert list(fake_pcap) == [] + + +@pytest.mark.parametrize('n_packets', [10]) +def test_pcap_read_wrong_ports(fake_meta, fake_pcap_path) -> None: + """Check specifying wrong ports.""" + fake_pcap = pcap.Pcap(fake_pcap_path, + fake_meta, + lidar_port=7505, + imu_port=7506) + assert fake_pcap.ports == (7505, 7506) + assert fake_pcap._guesses == [] + assert list(fake_pcap) == [] + + +@pytest.mark.parametrize('n_packets', [10]) +def test_pcap_guess_one_port_invalid(fake_meta, fake_pcap_path) -> None: + """Check that a port belonging to another pair isn't inferred. + + Capture contains data on (7502, 7503), but user expects lidar data on 7505. + """ + fake_pcap = pcap.Pcap(fake_pcap_path, + fake_meta, + lidar_port=7505, + imu_port=0) + assert fake_pcap._guesses == [] + assert fake_pcap.ports == (7505, 0) + assert list(fake_pcap) == [] + + +@pytest.mark.parametrize('n_packets', [10]) +@pytest.mark.parametrize('lidar_imu_frac', [1.0]) +def test_pcap_guess_one_port_valid(fake_meta, fake_pcap_path) -> None: + """Check that an unpaired port can be infered. + + Capture contains just lidar data on 7502, and user expects imu on 7503. + """ + fake_pcap = pcap.Pcap(fake_pcap_path, + fake_meta, + lidar_port=0, + imu_port=7503) + assert fake_pcap._guesses == [(7502, 0)] # no imu packets, no guess + assert fake_pcap.ports == (7502, 7503) + assert len(list(fake_pcap)) == 10 -@pytest.mark.parametrize('test_key', ['legacy-2.0']) @pytest.mark.parametrize('n_packets', [10]) -def test_pcap_read_10(pcap_obj) -> None: +def test_pcap_read_10(fake_pcap) -> None: """Check that reading a test pcap produces the right number of packets.""" - assert pcap_obj.ports == (7502, 7503) - assert len(list(pcap_obj)) == 10 + assert fake_pcap.ports == (7502, 7503) + assert len(list(fake_pcap)) == 10 + + +@pytest.mark.parametrize('n_packets', [10]) +def test_pcap_infer_one_port(fake_meta, fake_pcap_path) -> None: + """Check that a matching port is inferred when one is specified. """ + fake_pcap = pcap.Pcap(fake_pcap_path, + fake_meta, + lidar_port=0, + imu_port=7503) + assert fake_pcap._guesses == [(7502, 7503)] + assert fake_pcap.ports == (7502, 7503) + assert len(list(fake_pcap)) == 10 -@pytest.mark.parametrize('test_key', ['legacy-2.0']) @pytest.mark.parametrize('n_packets', [10]) -def test_pcap_info_10(pcap_path, meta) -> None: +def test_pcap_info_10(fake_meta, fake_pcap_path) -> None: """Test reading packet headers with private helper.""" ports: Dict[int, int] = defaultdict(int) sizes: Dict[int, int] = defaultdict(int) @@ -115,56 +161,51 @@ def test_pcap_info_10(pcap_path, meta) -> None: net: Dict[int, int] = defaultdict(int) af: Dict[int, int] = defaultdict(int) - for item in pcap._packet_info_stream(pcap_path): + for item in pcap._packet_info_stream(fake_pcap_path): ports[item.dst_port] += 1 sizes[item.payload_size] += 1 encap[item.encapsulation_protocol] += 1 net[item.network_protocol] += 1 af[item.ip_version] += 1 - # roundrobin -> 5 of each - assert ports == {7502: 5, 7503: 5} - assert sizes == {6464: 5, 48: 5} + assert ports[7502] + ports[7503] == 10 + assert sizes[6464] + sizes[48] == 10 assert encap == {ETH_PROTO: 10} assert net == {UDP_PROTO: 10} assert af == {4: 10} -@pytest.mark.parametrize('test_key', ['legacy-2.0']) @pytest.mark.parametrize('n_packets', [10]) @pytest.mark.parametrize('use_sll', [True, False]) -def test_pcap_info_encap_proto(pcap_path, use_sll) -> None: +def test_pcap_info_encap_proto(fake_pcap_path, use_sll) -> None: """Test reading/writing pcaps with different encapsulation.""" encap: Dict[int, int] = defaultdict(int) - for item in pcap._packet_info_stream(pcap_path): + for item in pcap._packet_info_stream(fake_pcap_path): encap[item.encapsulation_protocol] += 1 proto = SLL_PROTO if use_sll else ETH_PROTO assert encap == {proto: 10} -@pytest.mark.parametrize('test_key', ['legacy-2.0']) -def test_pcap_reset(pcap_obj) -> None: +def test_pcap_reset(fake_pcap) -> None: """Test that resetting a pcap after reading works.""" - packets1 = list(pcap_obj) - pcap_obj.reset() - packets2 = list(pcap_obj) + packets1 = list(fake_pcap) + fake_pcap.reset() + packets2 = list(fake_pcap) bufs1 = [bytes(p._data) for p in packets1] bufs2 = [bytes(p._data) for p in packets2] assert bufs1 == bufs2 -@pytest.mark.parametrize('test_key', ['legacy-2.0']) -def test_pcap_read_closed(pcap_obj) -> None: +def test_pcap_read_closed(fake_pcap: pcap.Pcap) -> None: """Check that reading from a closed pcap raises an error.""" - pcap_obj.close() + fake_pcap.close() with pytest.raises(ValueError): - next(iter(pcap_obj)) + next(iter(fake_pcap)) -@pytest.mark.parametrize('test_key', ['legacy-2.0']) @pytest.mark.parametrize("n_lidar, n_imu", [ pytest.param(1, 0, id="one lidar ether"), pytest.param(20, 0, id="multi lidar ether"), @@ -173,74 +214,52 @@ def test_pcap_read_closed(pcap_obj) -> None: pytest.param(1, 1, id="one each ether"), pytest.param(20, 20, id="multi each ether"), ]) -def test_read_write_lidar_imu(n_lidar, n_imu, meta, tmpdir) -> None: +def test_read_write_lidar_imu(n_lidar, n_imu, fake_meta, tmpdir) -> None: """Test that random packets read back from pcap are identical.""" - lidar_packets = islice(random_lidar_packets(meta), n_lidar) - imu_packets = islice(random_imu_packets(meta), n_imu) - in_packets: List[client.Packet] = list(chain(lidar_packets, imu_packets)) - - shuffle(in_packets) - - file_path = os.path.join(tmpdir, "pcap_test.pcap") + in_packets = list(fake_packets(fake_meta, n_lidar, n_imu)) + file_path = path.join(tmpdir, "pcap_test.pcap") pcap.record(in_packets, file_path) - out_packets = list(pcap.Pcap(file_path, meta)) + out_packets = list(pcap.Pcap(file_path, fake_meta)) out_bufs = [bytes(p._data) for p in out_packets] in_bufs = [bytes(p._data) for p in in_packets] assert in_bufs == out_bufs -@pytest.mark.parametrize('test_key', ['legacy-2.0']) -@pytest.mark.parametrize("mode", [ - pytest.param(RANDOM_FLOAT, id="random float timestamp"), -]) -def test_timestamp_float_read_write(mode, meta, tmpdir): - lidar_packets = islice(random_lidar_packets(meta, random_time=mode), 10) - imu_packets = islice(random_imu_packets(meta, random_time=mode), 10) - in_packets = list(chain(lidar_packets, imu_packets)) - - file_path = os.path.join(tmpdir, "pcap_test.pcap") +def test_timestamp_read_write(fake_meta, tmpdir) -> None: + """Check that timestamps are preserved by a round trip.""" + in_packets = list( + fake_packets(fake_meta, n_lidar=10, n_imu=10, timestamped=True)) + file_path = path.join(tmpdir, "pcap_test.pcap") pcap.record(in_packets, file_path) - out_packets = list(pcap.Pcap(file_path, meta)) - out_timestamps = [] - in_timestamps = [] - + out_packets = list(pcap.Pcap(file_path, fake_meta)) out_timestamps = [p.capture_timestamp for p in out_packets] in_timestamps = [p.capture_timestamp for p in in_packets] assert len(in_timestamps) == len(out_timestamps) - for i, o in zip(in_timestamps, out_timestamps): - # Make sure to deal with float rounding issues in the compare - assert i == pytest.approx(o, abs=1e-6) + assert in_timestamps == pytest.approx(out_timestamps) -@pytest.mark.parametrize('test_key', ['legacy-2.0']) -def test_no_timestamp_read_write(meta, tmpdir): - mode = NO_RANDOM_TIME - current_timestamp = time.time() - lidar_packets = islice(random_lidar_packets(meta, random_time=mode), 10) - imu_packets = islice(random_imu_packets(meta, random_time=mode), 10) - in_packets = list(chain(lidar_packets, imu_packets)) - - file_path = os.path.join(tmpdir, "pcap_test.pcap") +def test_no_timestamp_read_write(fake_meta, tmpdir) -> None: + """Check that capture timestamps are set when recording.""" + in_packets = list( + fake_packets(fake_meta, n_lidar=10, n_imu=10, timestamped=False)) + file_path = path.join(tmpdir, "pcap_test.pcap") + current_timestamp = time.time() pcap.record(in_packets, file_path) - out_packets = list(pcap.Pcap(file_path, meta)) - out_timestamps = [] - in_timestamps = [] - + out_packets = list(pcap.Pcap(file_path, fake_meta)) out_timestamps = [p.capture_timestamp for p in out_packets] in_timestamps = [p.capture_timestamp for p in in_packets] assert len(in_timestamps) == len(out_timestamps) - for i, o in zip(in_timestamps, out_timestamps): - assert i is None - assert current_timestamp == pytest.approx(o, abs=5e-1) + assert all(ts is None for ts in in_timestamps) + assert all(ts == pytest.approx(current_timestamp, abs=1.0) + for ts in out_timestamps) -@pytest.mark.parametrize('test_key', ['legacy-2.0']) @pytest.mark.parametrize( "n_lidar_timestamp, n_lidar_no_timestamp, n_imu_timestamp, n_imu_no_timestamp", [ @@ -253,25 +272,28 @@ def test_no_timestamp_read_write(meta, tmpdir): pytest.param(10, 10, 10, 10, id="mixed: all"), ]) def test_mixed_timestamp_write(n_lidar_timestamp, n_lidar_no_timestamp, - n_imu_timestamp, n_imu_no_timestamp, meta, + n_imu_timestamp, n_imu_no_timestamp, fake_meta, tmpdir) -> None: - - lidar_timestamp_packets = islice( - random_lidar_packets(meta, random_time=RANDOM_FLOAT), - n_lidar_timestamp) - lidar_no_timestamp_packets = islice( - random_lidar_packets(meta, random_time=NO_RANDOM_TIME), - n_lidar_no_timestamp) - imu_timestamp_packets = islice( - random_imu_packets(meta, random_time=RANDOM_FLOAT), n_imu_timestamp) - imu_no_timestamp_packets = islice( - random_imu_packets(meta, random_time=NO_RANDOM_TIME), - n_imu_no_timestamp) + """Test recording mixed (un)timestamped packets fails.""" + + lidar_ts_packets = fake_packets(fake_meta, + n_lidar=n_lidar_timestamp, + timestamped=True) + lidar_no_ts_packets = fake_packets(fake_meta, + n_lidar=n_lidar_no_timestamp, + timestamped=False) + imu_ts_packets = fake_packets(fake_meta, + n_imu=n_imu_timestamp, + timestamped=True) + imu_no_ts_packets = fake_packets(fake_meta, + n_imu=n_imu_no_timestamp, + timestamped=False) in_packets: List[client.Packet] = list( - chain(lidar_timestamp_packets, lidar_no_timestamp_packets, - imu_timestamp_packets, imu_no_timestamp_packets)) + chain(lidar_ts_packets, lidar_no_ts_packets, imu_ts_packets, + imu_no_ts_packets)) + shuffle(in_packets) - file_path = os.path.join(tmpdir, "pcap_test.pcap") + file_path = path.join(tmpdir, "pcap_test.pcap") yes_timestamps = n_lidar_timestamp + n_imu_timestamp no_timestamps = n_lidar_no_timestamp + n_imu_no_timestamp @@ -284,19 +306,20 @@ def test_mixed_timestamp_write(n_lidar_timestamp, n_lidar_no_timestamp, def test_write_nonsensical_packet_type(tmpdir) -> None: - file_path = os.path.join(tmpdir, "pcap_test.pcap") + """Check that writing nonsense raises an error and cleans up.""" + file_path = path.join(tmpdir, "pcap_test.pcap") in_packets = [42] with pytest.raises(ValueError): pcap.record(in_packets, file_path) # type: ignore - assert not os.path.exists(file_path), "Didn't clean up empty file" + assert not path.exists(file_path), "Didn't clean up empty file" -@pytest.mark.parametrize('test_key', ['legacy-2.0']) -def test_lidar_guess_error(meta, tmpdir) -> None: - packets = islice(random_lidar_packets(meta), 2) - file_path = os.path.join(tmpdir, "pcap_test.pcap") +def test_lidar_guess_ambiguous(fake_meta, tmpdir) -> None: + """Test reading when there's more than one possible lidar port.""" + packets = fake_packets(fake_meta, n_lidar=2) + file_path = path.join(tmpdir, "pcap_test.pcap") buf_size = 2**16 handle = _pcap.record_initialize(file_path, "127.0.0.1", "127.0.0.1", @@ -307,15 +330,16 @@ def test_lidar_guess_error(meta, tmpdir) -> None: finally: _pcap.record_uninitialize(handle) - source = pcap.Pcap(file_path, meta) + source = pcap.Pcap(file_path, fake_meta) assert len(source._guesses) > 1 + assert source.ports == (7503, 0) # arbitrary but deterministic assert len(list(source)) == 1 -@pytest.mark.parametrize('test_key', ['legacy-2.0']) -def test_imu_guess_error(meta, tmpdir) -> None: - packets = islice(random_imu_packets(meta), 2) - file_path = os.path.join(tmpdir, "pcap_test.pcap") +def test_imu_guess_ambiguous(fake_meta, tmpdir) -> None: + """Test reading when there's more than one possible imu port.""" + packets = fake_packets(fake_meta, n_imu=2) + file_path = path.join(tmpdir, "pcap_test.pcap") buf_size = 2**16 handle = _pcap.record_initialize(file_path, "127.0.0.1", "127.0.0.1", @@ -326,6 +350,36 @@ def test_imu_guess_error(meta, tmpdir) -> None: finally: _pcap.record_uninitialize(handle) - source = pcap.Pcap(file_path, meta) + source = pcap.Pcap(file_path, fake_meta) assert len(source._guesses) > 1 + assert source.ports == (0, 7503) # arbitrary but deterministic assert len(list(source)) == 1 + + +def test_pcap_read_real(real_pcap: pcap.Pcap) -> None: + """Sanity check reading pcaps with real data.""" + + assert len(real_pcap._guesses) == 1 + + # lidar data should be on 7502 + assert real_pcap.ports[0] == 7502 + + packets = list(real_pcap) + lidar_packets = [p for p in packets if isinstance(p, client.LidarPacket)] + + # test data should contain one frame of 1024-mode data + assert len(lidar_packets) == 64 + + # and should have timestamps + assert all(p.capture_timestamp is not None for p in packets) + + +def test_pcap_guess_real(meta: client.SensorInfo, real_pcap_path: str) -> None: + """Check that lidar port for real data can inferred.""" + + meta_no_ports = copy(meta) + meta_no_ports.udp_port_lidar = 0 + meta_no_ports.udp_port_imu = 0 + + real_pcap = pcap.Pcap(real_pcap_path, meta_no_ports) + assert real_pcap.ports[0] == 7502