diff --git a/CHANGELOG.rst b/CHANGELOG.rst index c2b14384..f1df3424 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,33 @@ Changelog ========= +[20240510] [0.11.1] +=================== + +Important notes +--------------- + +* [BREAKING] the ``open_source`` method now returns a ``ScanSource`` by default, not a ``MultiScanSource``. + +Python SDK +---------- + +* Updated the ``open_source`` documentation. +* Fixed an issue that caused the viz to redraw when the mouse cursor is moved. + +ouster_client +------------- + +* Improved the client initialization latency. + +mapping +------- + +* Fixed several issues with the documentation. + + [20240425] [0.11.0] -========================= +=================== Important notes --------------- diff --git a/CMakeLists.txt b/CMakeLists.txt index 40b60181..5ebbdd0b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,7 +16,7 @@ include(VcpkgEnv) project(ouster_example VERSION 20231031) # generate version header -set(OusterSDK_VERSION_STRING 0.11.0) +set(OusterSDK_VERSION_STRING 0.11.1) include(VersionGen) # ==== Options ==== diff --git a/docs/cli/mapping-sessions.rst b/docs/cli/mapping-sessions.rst index fc1304ac..bb9ecb81 100644 --- a/docs/cli/mapping-sessions.rst +++ b/docs/cli/mapping-sessions.rst @@ -4,6 +4,7 @@ Start mapping with the Ouster-CLI .. _ouster-cli-mapping: + Installation ------------ @@ -29,29 +30,34 @@ Mapping Tools After installing the Ouster SDK and mapping dependencies, you can explore various mapping tools using a connected Ouster sensor or a PCAP/OSF file. -Use ``ouster-cli`` to view the available commands and options you can use ``--help``. Try the -following command: +To explore and configure the parameters of the SLAM algorithm, you can use the ``--help`` flag +to view the available options. .. code:: bash - ouster-cli source / --help + ouster-cli source / slam --help -Currently, there are two main commands: ``slam`` and ``save``. You can further explore each -command by accessing their respective submenus using the ``--help`` flag. For example: +The ``slam`` command can be combined with either or both the ``save`` and ``viz`` commands. +You can further explore each command in detail by accessing their respective submenus +using the ``--help`` flag. .. code:: bash - ouster-cli source / slam --help + ouster-cli source / slam save --help + +.. code:: bash + + ouster-cli source / slam viz --help SLAM Command ------------ -Simultaneous localization and mapping (SLAM) is a technique that enables a system to construct +Simultaneous Localization and Mapping (SLAM) is a technique that enables a system to construct a map of its surroundings while simultaneously determining its own position on that map. -The Ouster SDK slam command writes lidar scans with per-column poses into an OSF file, an open-source -custom file format for which Ouster provides conversion capabilities, allowing for the -reconstruction of a detailed and precise map later. + +We use the slam algorithm to determine the lidar movement trajectory, correct motion +distortion and reconstruct a detailed and precise point cloud map. Connect to a sensor or use a PCAP/OSF file :ref:`Download Sample PCAP File ` @@ -64,7 +70,7 @@ Then execute the following command: .. code:: bash - ouster-cli source / slam viz -o sample.osf + ouster-cli source / slam viz -e exit save sample.osf .. note:: @@ -72,16 +78,80 @@ Then execute the following command: with the actual file path and name of the PCAP/OSF file. Similarly, make the necessary substitutions in the subsequent commands. -The terminal will display details such as the output filename and the processing duration. The -output filename must have the .osf extension in order to be used by the ``save`` command. -You can adjust settings such as point size, color, switch between 2D images, and pause playback in the visualizer, among other options. More details can be found at the :ref:`Ouster Visualizer ` +Save Command +------------ + +The ``save`` command stores the lidarscan and the lidar movement trajectory into a OSF file by +specifying a filename with a .osf extension. This OSF file will be used for accumulated point +cloud generation and the other post-process tools we offer in the future. + +.. code:: bash + + ouster-cli source / slam save sample.osf + +The ``save`` command can also be used to generated an accumulated point cloud map using a +SLAM-generated OSF file in LAS (.las), PLY (.ply), or PCD (.pcd) format. +The output format depends on the extension of the output filename. +For example, to convert the OSF file we generated using the ``slam`` command to PLY format, +we can simply use the following: + +.. code:: bash + + ouster-cli source sample.osf save output.ply + +You can utilize the ``slam`` command with the ``save`` command to directly generate a cumulative +point cloud map. However, please be aware that this combined process can be resource-intensive. +We recommend using this approach with a PCAP/OSF file rather than with a live sensor to avoid +SLAM performance degradation. + +.. code:: bash + + ouster-cli source slam save output.ply + +The accumulated point cloud data is automatically split and downsampleed into multiple files to +prevent exporting a huge size file. The terminal will display details, and you will see the +following printout for each output file: + +.. code:: bash + + Output file: output-000.ply + 3932160 points accumulated during this period, + 154228 near points are removed [3.92 %], + 1475955 down sampling points are removed [37.54 %], + 2213506 zero range points are removed [56.29 %], + 88471 points are saved [2.25 %]. + +Use the ``--help`` flag for more information such as adjusting the minimal range, selecting +different fields as values, and changing the point cloud downsampling scale etc. + +You can use an open source software `CloudCompare`_ to import and view the generated point cloud +data files. + +Viz Command +----------- -Accumulated Scan in SLAM command visulizer ------------------------------------------- +The ``viz`` command enables visualizing the accumulated point cloud generation during the +SLAM process. By default, the viz operates in looping mode, meaning the visualiation will +continuously replay the source file. + +.. code:: bash + + ouster-cli source / slam viz + +When combining the ``viz`` and ``save`` commands, the saving process will automatically terminate +after the first iteration, and then the SLAM process restarts for each subsequent lidar scan iteration. +To end the SLAM and visualization processes after the save operation completes, you can use ``ctrl + c``. +Alternatively, you can add ``-e exit`` to the ``viz`` command to terminate the process after a +complete iteration. + +.. code:: bash -Within the Ouster Visualizer, there is a visualization feature known as **ScansAccumulator**. This functionality represents a continuation of efforts to visualize lidar data by incorporating SLAM-generated poses stored within the ``LidarScan.pose`` property." + ouster-cli source / slam viz -e exit save sample.osf + + +**Scans Accumulation**: The viz command allows the user to customize ... Available view modes ~~~~~~~~~~~~~~~~~~~~~ @@ -127,9 +197,10 @@ Dense accumulated clouds view (with every point of a scan) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ To obtain the densest view use the ``--accum-num N --accum-every 1`` params where ``N`` is the -number of clouds to accumulate (``N`` up to 100 is generally small enough to avoid slowing down the viz interface):: +number of clouds to accumulate (``N`` up to 100 is generally small enough to avoid slowing down +the viz interface):: - ouster-cli source / slam viz --accum-num 20 -o sample.osf + ouster-cli source / slam viz --accum-num 20 save sample.osf and the dense accumulated clouds result: @@ -141,14 +212,18 @@ and the dense accumulated clouds result: Overall map view (with poses) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -One of the main tasks we frequently need is a preview of the overall map. We can test this by using the generated OSF file, which was created with the above command and contains the SLAM-generated ``LidarScan.pose`` property. +One of the main tasks we frequently need is a preview of the overall map. We can test this by using +the generated OSF file, which was created with the above command and contains the +SLAM-generated ``LidarScan.pose`` property. :: ouster-cli source sample.osf viz --accum-num 20 \ --accum-every 0 --accum-every-m 10.5 --accum-map -r 0 -e stop -Here is a preview example of the overall map generated from the accumulated scan results. By utilizing the '-e stop' option, the visualizer stops once the replay process finishes, displaying the preview of the lidar trajectory: +Here is a preview example of the overall map generated from the accumulated scan results. +By utilizing the '-e stop' option, the visualizer stops once the replay process finishes, +displaying the preview of the lidar trajectory: .. figure:: /images/scans_accum_map_all_scan.png @@ -156,38 +231,6 @@ Here is a preview example of the overall map generated from the accumulated scan palette) -Save Command ------------- - -The ``save`` command can be used to convert the SLAM-generated OSF file to a point cloud data file -format such as LAS (.las), PLY (.ply), or PCD (.pcd). The output file format depends on the -extension of the output filename. Let's use the OSF file generated from the SLAM command -and convert it to a PLY file: - -.. code:: bash - - ouster-cli source sample.osf save output.ply - -The ``save`` command automatically splits and downsamples the trajectory-adjusted point cloud into -several files to prevent exporting a huge size file. The terminal will display details, and you -will see the following printout for each output file: - -.. code:: bash - - Output file: output1.ply - 3932160 points accumulated during this period, - 154228 near points are removed [3.92 %], - 1475955 down sampling points are removed [37.54 %], - 2213506 zero range points are removed [56.29 %], - 88471 points are saved [2.25 %]. - -You can adjust the minimal range, select different fields as values, and change the voxel size by -referring to the ``--help`` flag for more information. - -You can use an open source software `CloudCompare`_ to import and view the generated point cloud -data files. - - .. _Networking Guide: https://static.ouster.dev/sensor-docs/image_route1/image_route3/networking_guide/networking_guide.html .. _CloudCompare: https://www.cloudcompare.org/ diff --git a/docs/python/slam-api-example.rst b/docs/python/slam-api-example.rst index 708bed6d..a9eaeb3e 100644 --- a/docs/python/slam-api-example.rst +++ b/docs/python/slam-api-example.rst @@ -26,7 +26,7 @@ between consecutive scans from ouster.sdk import open_source from ouster.mapping.slam import KissBackend import numpy as np - scans = open_source(pcap_path, sensor_idx=0) + scans = open_source(pcap_path) slam = KissBackend(scans.metadata, max_range=75, min_range=1, voxel_size=1.0) last_scan_pose = np.eye(4) @@ -59,7 +59,7 @@ as well as for demonstration and feedback purposes. from functools import partial from ouster.viz import SimpleViz, ScansAccumulator from ouster.mapping.slam import KissBackend - scans = open_source(pcap_path, sensor_idx=0) + scans = open_source(pcap_path) slam = KissBackend(scans.metadata, max_range=75, min_range=1, voxel_size=1.0) scans_w_poses = map(partial(slam.update), scans) diff --git a/docs/python/using-scan-source.rst b/docs/python/using-scan-source.rst index 6c078308..459b881b 100644 --- a/docs/python/using-scan-source.rst +++ b/docs/python/using-scan-source.rst @@ -24,38 +24,39 @@ can be accomplished as follows: >>> pcap_path = '' >>> metadata_path = '' >>> from ouster.sdk import open_source - >>> source = open_source(pcap_path, sensor_idx=0, meta=[metadata_path]) + >>> source = open_source(pcap_path, meta=[metadata_path]) The ``source`` handle here acts the same as the handle returned by the ``pcap.Pcap`` constructor, with some extra capabilities that we will cover later. -Notice here that besides the ``pcap_path`` we pass two additional parameters: ``sensor_idx`` with a value -of zero, and ``meta`` which we set to the ``metadata_path`` to point to the sensor metadata associated with -the pcap file we are trying to open. Both parameters are optional and can be omitted. In case the ``meta`` -parameter was not omitted, the ``open_source`` method will attempt to locate the metadata associated with -the pcap file based on location and the pcap file prefix. That being said, if ``SAMPLE_DATA_JSON_PATH`` is -located in the same folder as ``SAMPLE_DATA_PCAP_PATH`` and the two files share a prefix we can simplify the -above call to: +Notice here that rather than we try to load and parse the metadata ourselves we only need to pass to metadata +to the method through ``meta`` parameter and the method will take care of loading it and associating it with the +source object. The ``meta`` parameter however is optional and can be omitted. When the ``meta`` parameter is not +set explicity the ``open_source`` method will attempt to locate the metadata automatically for us and we can reduce +the call to: .. code:: python - >>> source = open_source(pcap_path, sensor_idx=0) + >>> source = open_source(pcap_path) +However if metadata file is not in the same folder as the pcap and don't have a shared name prefix the method will +fail. -The second parameter, ``sensor_idx``, allows users to select a specific sensor from the selected source. -That is because starting with ouster-sdk v0.11 Ouster added support for working with sensor data collected from -multiple sensors. The ``open_source`` method by default returns the more complete interface ``MultiScanSource`` -which has the capability to interact with multiple sensor streams, which we will in next section. Setting the -value of ``sensor_idx`` to zero tells ``open_source`` we are only interested in LidarScan data coming from the -first sensor from this specific pcap file in case the file had more than one sensor. By doing so, the -``open_source`` method returns a less sophisticated interface ``ScanSource`` which is more familiar to SDK users -from previous versions. -The main different between the ``MultiScanSource`` and the ``ScanSource`` is the expected return of some -of the object methods. For example, when creating an iterator for a ``ScanSource`` object, the user would get -a single ``LidarScan`` object per iteration. Iterating over the contents of a ``MultiScanSource`` object always -yields a **list** of ``LidarScan(s)`` per iteration corresponding to the number of sensors stored in the pcap -file or whatever source type is being used. This is true even when the pcap file contains data for a single sensor. +.. note:: + Another optional but important parameter for the ``open_source`` method is ``sensor_idx``. This paramter is to zero + by default, which should always be the case unless the pcap file that you are using (or osf or any LidarScan storage) + contains scans from more than one sensor, in this case, users can set the ``sensor_idx`` to a any value between zero + and ``sensors_count -1`` to access and manipulate scans from a specific sensor by the order they appear in the file. + Alternatively, if users set the value of ``sensor_idx`` to ``-1`` then ``open_source`` will return a slightly differnt + interface from ``ScanSource`` which is the ``MultiScanSource`` this interface and as the name suggests allows users to + work with sensor data collected from multiple sensors at the same time. + + The main different between the ``MultiScanSource`` and the ``ScanSource`` is the expected return of some of the object + methods. For example, when creating an iterator for a ``ScanSource`` object, the user would get a single ``LidarScan`` + object per iteration. Iterating over the contents of a ``MultiScanSource`` object always yields a **list** of + ``LidarScan(s)`` per iteration corresponding to the number of sensors stored in the pcap file or whatever source type + is being used. This is true even when the pcap file contains data for a single sensor. On the other hand, if the user wants to open an osf file or access the a live sensor, all that changes is url @@ -65,7 +66,7 @@ of the source. For example, to interact with a live sensor the user can execute >>> sensor_url = '' >>> from ouster.sdk import open_source - >>> source = open_source(sensor_url, sensor_idx=0) + >>> source = open_source(sensor_url) Obtaining sensor metadata @@ -96,8 +97,7 @@ scans. We can achieve that using: ... if ctr == 10: ... break - -As we noted earlier, if we don't supply ``sensor_idx=0`` to the ``open_source`` method, the method will construct a +As we noted earlier, if we set ``sensor_idx=-1`` when invoking ``open_source`` method, the method will construct a ``MultiScanSource``, which always addresses a group of sensors. Thus, when iterating over the ``source`` the user receives a collated set of scans from the addressed sensors per iteration. The ``MultiScanSource`` examines the timestamp of every scan from every sensor and returns a list of scans that fit within the same time window as single @@ -126,7 +126,6 @@ Note that when iterating over a ``MultiScanSource`` object, it always a list of source has only a single sensor. In this case, the iterator will yield a list with a single element per iteration. - Using indexing and slicing capabilities of a ScanSource ======================================================== @@ -142,7 +141,7 @@ source as an indexed one upon opening. Revisitng the previous pcap open example, >>> pcap_path = '' >>> from ouster.sdk import open_source - >>> source = open_source(pcap_path, sensor_idx=0, index=True) + >>> source = open_source(pcap_path, index=True) First note that we omitted the ``meta`` parameter since it can be populated automatically as we explained earlier. Second you will noticed that we introduced a new parameter ``index`` with its value set to ``True`` (default is false), diff --git a/docs/versions.json b/docs/versions.json index f87ea1d0..152af2c2 100644 --- a/docs/versions.json +++ b/docs/versions.json @@ -1,4 +1,11 @@ [ + { + "version": "0.11.0", + "tags": { + "sdkx": "sdk/0.11.0", + "sdk": "sdk/0.11.0" + } + }, { "version": "0.10.0", "tags": { diff --git a/ouster_client/src/client.cpp b/ouster_client/src/client.cpp index a5b21107..af3d2cd2 100644 --- a/ouster_client/src/client.cpp +++ b/ouster_client/src/client.cpp @@ -252,18 +252,21 @@ Json::Value collect_metadata(const std::string& hostname, int timeout_sec) { auto sensor_http = SensorHttp::create(hostname, timeout_sec); auto timeout_time = chrono::steady_clock::now() + chrono::seconds{timeout_sec}; - std::string status; + std::string status; // TODO: can remove this loop when we drop support for FW 2.4 - do { + while (true) { if (chrono::steady_clock::now() >= timeout_time) { throw std::runtime_error( "A timeout occurred while waiting for the sensor to " "initialize."); } - std::this_thread::sleep_for(1s); status = sensor_http->sensor_info()["status"].asString(); - } while (status == "INITIALIZING"); + if (status != "INITIALIZING") { + break; + } + std::this_thread::sleep_for(1s); + } try { auto metadata = sensor_http->metadata(); diff --git a/ouster_client/src/profile_extension.cpp b/ouster_client/src/profile_extension.cpp index eed240b8..86199ca3 100644 --- a/ouster_client/src/profile_extension.cpp +++ b/ouster_client/src/profile_extension.cpp @@ -112,8 +112,10 @@ void extend_udp_profile_lidar_strings(UDPProfileLidar profile, throw std::invalid_argument( "Lidar profile of given name already exists"); + // Make sure to only check the string for zero intialization. + // The profile enum can be 0 normally (and is for UNKNOWN). auto it = - std::find_if(begin, end, [](const auto& kv) { return kv.first == 0; }); + std::find_if(begin, end, [](const auto& kv) { return kv.second == 0; }); if (it == end) throw std::runtime_error("Limit of lidar profiles has been reached"); diff --git a/ouster_viz/src/point_viz.cpp b/ouster_viz/src/point_viz.cpp index 03580398..f99519d2 100644 --- a/ouster_viz/src/point_viz.cpp +++ b/ouster_viz/src/point_viz.cpp @@ -895,6 +895,7 @@ void add_default_controls(viz::PointViz& viz, std::mutex* mx) { constexpr double sensitivity = 0.3; viz.camera().yaw(sensitivity * dx); viz.camera().pitch(sensitivity * dy); + if (viz.update_on_input()) viz.update(); } else if (wc.mbutton_down) { // convert from screen coordinated to fractions of window size // TODO: factor out conversion? @@ -904,8 +905,8 @@ void add_default_controls(viz::PointViz& viz, std::mutex* mx) { dx *= 2.0 / window_diagonal; dy *= 2.0 / window_diagonal; viz.camera().dolly_xy(dx, dy); + if (viz.update_on_input()) viz.update(); } - if (viz.update_on_input()) viz.update(); return true; }); } diff --git a/python/README.rst b/python/README.rst index 73b58c2d..3779a1a1 100644 --- a/python/README.rst +++ b/python/README.rst @@ -12,7 +12,7 @@ sensor data in both languages. The SDK includes APIs for: * Querying and setting sensor configuration * Recording and reading data in pcap format -* Recording and reading data in :ref:`Open Sensor Format (OSF)` +* Recording and reading data in Open Sensor Format (OSF) * Reading and buffering sensor UDP data streams reliably * Conversion of raw data to range/signal/near_ir/reflectivity images (destaggering) * Efficient projection of range measurements to Cartesian (x, y, z) coordinates diff --git a/python/setup.py b/python/setup.py index afce641d..41025587 100644 --- a/python/setup.py +++ b/python/setup.py @@ -165,7 +165,7 @@ def install_requires(): env = os.environ.copy() skip_mapping = env.get('OUSTER_SDK_SKIP_MAPPING') if not skip_mapping: - install_requires.append('ouster-mapping==0.2.0; python_version >= "3.8" and python_version <= "3.12"') + install_requires.append('ouster-mapping==0.2.1; python_version >= "3.8" and python_version <= "3.12"') return install_requires diff --git a/python/src/ouster/cli/plugins/source.py b/python/src/ouster/cli/plugins/source.py index 093287ff..079b9dce 100644 --- a/python/src/ouster/cli/plugins/source.py +++ b/python/src/ouster/cli/plugins/source.py @@ -368,7 +368,7 @@ def process_commands(click_ctx: click.core.Context, callbacks: Iterable[SourceCo if extrinsics: resolved_extrinsics = np.array(extrinsics).reshape((4, 4)) - ctx.scan_source = open_source(source, sensor_idx=0, + ctx.scan_source = open_source(source, extrinsics=resolved_extrinsics, meta=meta, lidar_port=lidar_port, imu_port=imu_port, diff --git a/python/src/ouster/sdk/client/scan_source.py b/python/src/ouster/sdk/client/scan_source.py index ad345b34..d18195bb 100644 --- a/python/src/ouster/sdk/client/scan_source.py +++ b/python/src/ouster/sdk/client/scan_source.py @@ -9,7 +9,7 @@ class ScanSource(Protocol): @property def metadata(self) -> SensorInfo: - """A list of Metadata objects associated with the scan streams.""" + """A metadata object associated with the scan streams.""" ... @property diff --git a/python/src/ouster/sdk/open_source.py b/python/src/ouster/sdk/open_source.py index 3b9cdfb1..98d0d08f 100644 --- a/python/src/ouster/sdk/open_source.py +++ b/python/src/ouster/sdk/open_source.py @@ -16,7 +16,7 @@ } -def open_source(source_url: str, sensor_idx: int = -1, *args, +def open_source(source_url: str, sensor_idx: int = 0, *args, extrinsics: Optional[Union[str, np.ndarray, List[np.ndarray]]] = None, **kwargs) -> Union[ScanSource, MultiScanSource]: """ @@ -25,10 +25,11 @@ def open_source(source_url: str, sensor_idx: int = -1, *args, the url can contain the path to a pcap file or an osf file. alternatively, the url could contain a list of comma separated sensor hostnames or ips (current multisensor is not supprted) - - sensor_idx: If sensor_idx is set to a postive number the function - returns a ScanSource instead of MultiScanSource which is simpler - but can can handle one source. sensor_idx shouldn't exceed the - number of scan sources that the source_url refers to. + - sensor_idx: The sensor_idx parameter can be set to any value between + 0 and the number of addressable sensors within the source_url. This + returns the ScanSource interface (default is 0). If you want to work + with the more advanced MultiScanSource interface which supports + handling multiple sensors at the same time pass -1. - extrinsics: could be either a path to an extrinsics file, single 4x4 numpy array or a list of 4x4 numpy arrays. In case a single 4x4 numpy array was given while the scan_source had more than sensor then the diff --git a/python/tests/osf/test_osf_basics.py b/python/tests/osf/test_osf_basics.py index 55fcf66d..3bfb8674 100644 --- a/python/tests/osf/test_osf_basics.py +++ b/python/tests/osf/test_osf_basics.py @@ -27,9 +27,9 @@ def input_info(test_data_dir): def test_osf_scan_source_flags(input_osf_file): from ouster.sdk.client import ChanField - ss = open_source(str(input_osf_file), sensor_idx=0, flags=False) + ss = open_source(str(input_osf_file), flags=False) assert ss.fields.get(ChanField.FLAGS) is None - ss = open_source(str(input_osf_file), sensor_idx=0) + ss = open_source(str(input_osf_file)) assert ss.fields.get(ChanField.FLAGS) is not None diff --git a/python/tests/test_open_source.py b/python/tests/test_open_source.py index fbe6d74b..598efac6 100644 --- a/python/tests/test_open_source.py +++ b/python/tests/test_open_source.py @@ -57,5 +57,6 @@ def test_open_source_meta_pcap(): # the test file is different than what would be resolved ordinarily assert json_file_path not in resolve_metadata_multi(pcap_file_path) - src = open_source(pcap_file_path, meta=(json_file_path,)) + src = open_source(pcap_file_path, sensor_idx=-1, meta=(json_file_path,)) + # TODO: src._metadata_paths is not a standard field assert src._metadata_paths == [json_file_path] diff --git a/python/tests/test_resolve_extrinsics.py b/python/tests/test_resolve_extrinsics.py index 4125c235..70a584d2 100644 --- a/python/tests/test_resolve_extrinsics.py +++ b/python/tests/test_resolve_extrinsics.py @@ -88,25 +88,24 @@ def test_resolve_extrinscs_using_dir(): def test_open_source_with_file_that_has_no_valid_extrinscs(): - ss = open_source(source_url=PCAP_PATH_WITH_NO_EXT, sensor_idx=0) + ss = open_source(source_url=PCAP_PATH_WITH_NO_EXT) np.testing.assert_array_equal(ss.metadata.extrinsic, np.eye(4)) def test_open_source_with_file_that_has_no_valid_extrinscs_but_supply_array(): ss = open_source(source_url=PCAP_PATH_WITH_NO_EXT, - sensor_idx=0, extrinsics=np.ones((4, 4))) + extrinsics=np.ones((4, 4))) np.testing.assert_array_equal(ss.metadata.extrinsic, np.ones((4, 4))) def test_open_source_with_file_that_has_no_valid_extrinscs_but_supply_extrinscs_path(): ss = open_source(source_url=PCAP_PATH_WITH_NO_EXT, - sensor_idx=0, extrinsics=EXT_PATH) + extrinsics=EXT_PATH) array_cmp = ss.metadata.extrinsic != np.eye(4) assert array_cmp.any() def test_open_source_with_file_that_has_valid_extrinscs(): - ss = open_source(source_url=PCAP_PATH_WITH_EXT, - sensor_idx=0) + ss = open_source(source_url=PCAP_PATH_WITH_EXT) array_cmp = ss.metadata.extrinsic != np.eye(4) assert array_cmp.any()