├── .gitattributes
├── .gitignore
├── Dockerfile
├── LICENSE
├── README.md
├── cuvslam
├── aarch64
│ ├── cuvslam
│ │ ├── __init__.py
│ │ ├── cuvslam.pyi
│ │ ├── libcuvslam.so
│ │ └── pycuvslam.so
│ ├── pyproject.toml
│ └── setup.py
└── x86
│ ├── cuvslam
│ ├── __init__.py
│ ├── cuvslam.pyi
│ ├── libcuvslam.so
│ └── pycuvslam.so
│ ├── pyproject.toml
│ └── setup.py
├── docs
├── README.md
├── tutorial_euroc.jpg
├── tutorial_euroc.md
├── tutorial_kitti.jpg
├── tutorial_kitti.md
├── tutorial_multicamera_edex.gif
├── tutorial_multicamera_edex.md
├── tutorial_oakd.md
├── tutorial_oakd_stereo.gif
├── tutorial_realsense.md
├── tutorial_realsense_stereo.gif
└── tutorial_realsense_vio.gif
├── examples
├── euroc
│ ├── dataset
│ │ ├── sensor_cam0.yaml
│ │ ├── sensor_cam1.yaml
│ │ └── sensor_imu0.yaml
│ ├── dataset_utils.py
│ └── track_euroc.py
├── kitti
│ └── track_kitti.py
├── multicamera_edex
│ ├── dataset_utils.py
│ └── track_multicamera.py
├── oak-d
│ └── run_stereo.py
├── realsense
│ ├── camera_utils.py
│ ├── run_stereo.py
│ ├── run_vio.py
│ └── visualizer.py
└── requirements.txt
├── pycuvslam.gif
└── run_docker.sh
/.gitattributes:
--------------------------------------------------------------------------------
1 | # Images
2 | *.bmp filter=lfs diff=lfs merge=lfs -text
3 | *.gif filter=lfs diff=lfs merge=lfs -text
4 | *.jpg filter=lfs diff=lfs merge=lfs -text
5 | *.png filter=lfs diff=lfs merge=lfs -text
6 | *.psd filter=lfs diff=lfs merge=lfs -text
7 | *.tga filter=lfs diff=lfs merge=lfs -text
8 |
9 | # Archives
10 | *.gz filter=lfs diff=lfs merge=lfs -text
11 | *.tar filter=lfs diff=lfs merge=lfs -text
12 | *.zip filter=lfs diff=lfs merge=lfs -text
13 |
14 | # Documents
15 | *.pdf filter=lfs diff=lfs merge=lfs -text
16 |
17 | # Shared libraries
18 | *.so filter=lfs diff=lfs merge=lfs -text
19 | *.so.* filter=lfs diff=lfs merge=lfs -text
20 |
21 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | *.egg-info
2 | .idea
3 | .venv
4 | .vscode
5 | __pycache__
6 | build
7 | dataset
8 |
--------------------------------------------------------------------------------
/Dockerfile:
--------------------------------------------------------------------------------
1 | FROM nvcr.io/nvidia/cuda:12.6.1-runtime-ubuntu22.04@sha256:aa0da342b530a7dd2630b17721ee907fc9210b4e159d67392c4c373bef642483
2 |
3 | RUN apt-get update \
4 | && DEBIAN_FRONTEND="noninteractive" apt-get install -y --no-install-recommends --allow-change-held-packages \
5 | libgtk-3-dev \
6 | libpython3.10 \
7 | libxkbcommon-x11-0 \
8 | python3-pip \
9 | unzip \
10 | vulkan-tools \
11 | wget \
12 | && apt-get clean
13 |
14 | RUN pip3 install --upgrade pip
15 |
16 | WORKDIR /pycuvslam
17 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | NVIDIA PyCuVSLAM SOFTWARE LICENSE
2 |
3 |
4 |
5 | This license is a legal agreement between you and NVIDIA Corporation ("NVIDIA") and governs the use of the NVIDIA PyCuVSLAM software and materials provided hereunder (“SOFTWARE”).
6 |
7 |
8 |
9 | This license can be accepted only by an adult of legal age of majority in the country in which the SOFTWARE is used.
10 |
11 |
12 |
13 | If you are entering into this license on behalf of a company or other legal entity, you represent that you have the legal authority to bind the entity to this license, in which case “you” will mean the entity you represent.
14 |
15 |
16 |
17 | If you don’t have the required age or authority to accept this license, or if you don’t accept all the terms and conditions of this license, do not download, install or use the SOFTWARE.
18 |
19 |
20 |
21 | You agree to use the SOFTWARE only for purposes that are permitted by (a) this license, and (b) any applicable law, regulation or generally accepted practices or guidelines in the relevant jurisdictions.
22 |
23 |
24 |
25 | 1. LICENSE. Subject to the terms of this license, NVIDIA hereby grants you a non-exclusive, non-transferable license, without the right to sublicense (except as expressly provided in this license) to:
26 |
27 | a. Install and use the SOFTWARE,
28 |
29 | b. Modify and create derivative works of sample or reference source code delivered in the SOFTWARE, and
30 |
31 | c. Distribute any part of the SOFTWARE (i) as incorporated into a software application that has material additional functionality beyond the included portions of the SOFTWARE, or (ii) unmodified in binary format, in each case subject to the distribution requirements indicated in this license.
32 |
33 | All the foregoing (a) through (c) are only for non-commercial purposes, where ‘non-commercial’ means for research or evaluation purposes only (“Purpose)”
34 |
35 | 2. DISTRIBUTION REQUIREMENTS. These are the distribution requirements for you to exercise the distribution grant above:
36 |
37 | a. The following notice shall be included in modifications and derivative works of source code distributed: “This software contains source code provided by NVIDIA Corporation.”
38 |
39 | b. You agree to distribute the SOFTWARE subject to the terms at least as protective as the terms of this license, including (without limitation) terms relating to the license grant, non-commercial limitation described in Section 1(c) above, license restrictions and protection of NVIDIA’s intellectual property rights. Additionally, you agree that you will protect the privacy, security and legal rights of your application users.
40 |
41 | c. You agree to notify NVIDIA in writing of any known or suspected distribution or use of the SOFTWARE not in compliance with the requirements of this license, and to enforce the terms of your agreements with respect to the distributed portions of the SOFTWARE.
42 |
43 | 3. AUTHORIZED USERS. You may allow employees and contractors of your entity or of your subsidiary(ies) to access and use the SOFTWARE from your secure network to perform work on your behalf. If you are an academic institution you may allow users enrolled or employed by the academic institution to access and use the SOFTWARE from your secure network. You are responsible for the compliance with the terms of this license by your authorized users.
44 |
45 |
46 |
47 | 4. LIMITATIONS. Your license to use the SOFTWARE is restricted as follows:
48 |
49 | a. Use the SOFTWARE and derivative works for any purpose other than the Purpose;
50 |
51 | b. The SOFTWARE is licensed for you to develop applications only for their use in systems with NVIDIA GPUs.
52 |
53 | c. You may not reverse engineer, decompile or disassemble, or remove copyright or other proprietary notices from any portion of the SOFTWARE or copies of the SOFTWARE.
54 |
55 | d. Except as expressly stated above in this license, you may not sell, rent, sublicense, transfer, distribute, modify, or create derivative works of any portion of the SOFTWARE.
56 |
57 | e. Unless you have an agreement with NVIDIA for this purpose, you may not indicate that an application created with the SOFTWARE is sponsored or endorsed by NVIDIA.
58 |
59 | f. You may not bypass, disable, or circumvent any technical limitation, encryption, security, digital rights management or authentication mechanism in the SOFTWARE.
60 |
61 | g. You may not use the SOFTWARE in any manner that would cause it to become subject to an open source software license. As examples, licenses that require as a condition of use, modification, and/or distribution that the SOFTWARE be: (i) disclosed or distributed in source code form; (ii) licensed for the purpose of making derivative works; or (iii) redistributable at no charge.
62 |
63 | h. You acknowledge that the SOFTWARE as delivered is not tested or certified by NVIDIA for use in connection with the design, construction, maintenance, and/or operation of any system where the use or failure of such system could result in a situation that threatens the safety of human life or results in catastrophic damages (each, a "Critical Application"). Examples of Critical Applications include use in avionics, navigation, autonomous vehicle applications, ai solutions for automotive products, military, medical, life support or other life critical applications. NVIDIA shall not be liable to you or any third party, in whole or in part, for any claims or damages arising from such uses. You are solely responsible for ensuring that any product or service developed with the SOFTWARE as a whole includes sufficient features to comply with all applicable legal and regulatory standards and requirements.
64 |
65 | i. You agree to defend, indemnify and hold harmless NVIDIA and its affiliates, and their respective employees, contractors, agents, officers and directors, from and against any and all claims, damages, obligations, losses, liabilities, costs or debt, fines, restitutions and expenses (including but not limited to attorney’s fees and costs incident to establishing the right of indemnification) arising out of or related to your use of goods and/or services that include or utilize the SOFTWARE, or for use of the SOFTWARE outside of the scope of this license or not in compliance with its terms.
66 |
67 |
68 |
69 | 5. UPDATES. NVIDIA may, at its option, make available patches, workarounds or other updates to this SOFTWARE. Unless the updates are provided with their separate governing terms, they are deemed part of the SOFTWARE licensed to you as provided in this license.
70 |
71 |
72 |
73 | 6. PRE-RELEASE VERSIONS. SOFTWARE versions identified as alpha, beta, preview, early access or otherwise as pre-release may not be fully functional, may contain errors or design flaws, and may have reduced or different security, privacy, availability, and reliability standards relative to commercial versions of NVIDIA software and materials. You may use a pre-release SOFTWARE version at your own risk, understanding that these versions are not intended for use in production or business-critical systems.
74 |
75 |
76 |
77 | 7. COMPONENTS UNDER OTHER LICENSES. The SOFTWARE may include NVIDIA or third-party components with separate legal notices or terms as may be described in proprietary notices accompanying the SOFTWARE, such as components governed by open source software licenses. If and to the extent there is a conflict between the terms in this license and the license terms associated with a component, the license terms associated with the component controls only to the extent necessary to resolve the conflict.
78 |
79 |
80 |
81 | 8. OWNERSHIP.
82 |
83 |
84 |
85 | 8.1 NVIDIA reserves all rights, title and interest in and to the SOFTWARE not expressly granted to you under this license. NVIDIA and its suppliers hold all rights, title and interest in and to the SOFTWARE, including their respective intellectual property rights. The SOFTWARE is copyrighted and protected by the laws of the United States and other countries, and international treaty provisions.
86 |
87 |
88 |
89 | 8.2 Subject to the rights of NVIDIA and its suppliers in the SOFTWARE, you hold all rights, title and interest in and to your applications and your derivative works of the sample or reference source code delivered in the SOFTWARE including their respective intellectual property rights. With respect to source code samples or reference source code licensed to you, NVIDIA and its affiliates are free to continue independently developing source code samples and you covenant not to sue NVIDIA, its affiliates or their licensees with respect to later versions of NVIDIA released source code.
90 |
91 |
92 |
93 | 9. FEEDBACK. You may, but are not obligated to, provide to NVIDIA Feedback. “Feedback” means suggestions, fixes, modifications, feature requests or other feedback regarding the SOFTWARE. Feedback, even if designated as confidential by you, shall not create any confidentiality obligation for NVIDIA. NVIDIA and its designees have a perpetual, non-exclusive, worldwide, irrevocable license to use, reproduce, publicly display, modify, create derivative works of, license, sublicense, and otherwise distribute and exploit Feedback as NVIDIA sees fit without payment and without obligation or restriction of any kind on account of intellectual property rights or otherwise.
94 |
95 |
96 |
97 | 10. NO WARRANTIES. THE SOFTWARE IS PROVIDED AS-IS. TO THE MAXIMUM EXTENT PERMITTED BY APPLICABLE LAW NVIDIA AND ITS AFFILIATES EXPRESSLY DISCLAIM ALL WARRANTIES OF ANY KIND OR NATURE, WHETHER EXPRESS, IMPLIED OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, WARRANTIES OF MERCHANTABILITY, NON-INFRINGEMENT, OR FITNESS FOR A PARTICULAR PURPOSE. NVIDIA DOES NOT WARRANT THAT THE SOFTWARE WILL MEET YOUR REQUIREMENTS OR THAT THE OPERATION THEREOF WILL BE UNINTERRUPTED OR ERROR-FREE, OR THAT ALL ERRORS WILL BE CORRECTED.
98 |
99 |
100 |
101 | 11. LIMITATIONS OF LIABILITY. TO THE MAXIMUM EXTENT PERMITTED BY APPLICABLE LAW NVIDIA AND ITS AFFILIATES SHALL NOT BE LIABLE FOR ANY SPECIAL, INCIDENTAL, PUNITIVE OR CONSEQUENTIAL DAMAGES, OR FOR ANY LOST PROFITS, PROJECT DELAYS, LOSS OF USE, LOSS OF DATA OR LOSS OF GOODWILL, OR THE COSTS OF PROCURING SUBSTITUTE PRODUCTS, ARISING OUT OF OR IN CONNECTION WITH THIS LICENSE OR THE USE OR PERFORMANCE OF THE SOFTWARE, WHETHER SUCH LIABILITY ARISES FROM ANY CLAIM BASED UPON BREACH OF CONTRACT, BREACH OF WARRANTY, TORT (INCLUDING NEGLIGENCE), PRODUCT LIABILITY OR ANY OTHER CAUSE OF ACTION OR THEORY OF LIABILITY, EVEN IF NVIDIA HAS PREVIOUSLY BEEN ADVISED OF, OR COULD REASONABLY HAVE FORESEEN, THE POSSIBILITY OF SUCH DAMAGES. IN NO EVENT WILL NVIDIA’S AND ITS AFFILIATES TOTAL CUMULATIVE LIABILITY UNDER OR ARISING OUT OF THIS LICENSE EXCEED US$10.00. THE NATURE OF THE LIABILITY OR THE NUMBER OF CLAIMS OR SUITS SHALL NOT ENLARGE OR EXTEND THIS LIMIT.
102 |
103 |
104 |
105 | 12. TERMINATION. Your rights under this license will terminate automatically without notice from NVIDIA if you fail to comply with any term and condition of this license or if you commence or participate in any legal proceeding against NVIDIA with respect to the SOFTWARE. NVIDIA may terminate this license with advance written notice to you, if NVIDIA decides to no longer provide the SOFTWARE in a country or, in NVIDIA’s sole discretion, the continued use of it is no longer commercially viable. Upon any termination of this license, you agree to promptly discontinue use of the SOFTWARE and destroy all copies in your possession or control. Your prior distributions in accordance with this license are not affected by the termination of this license. All provisions of this license will survive termination, except for the license granted to you.
106 |
107 |
108 |
109 | 13. APPLICABLE LAW. This license will be governed in all respects by the laws of the United States and of the State of Delaware, without regard to the conflicts of laws principles. The United Nations Convention on Contracts for the International Sale of Goods is specifically disclaimed. You agree to all terms of this license in the English language. The state or federal courts residing in Santa Clara County, California shall have exclusive jurisdiction over any dispute or claim arising out of this license. Notwithstanding this, you agree that NVIDIA shall still be allowed to apply for injunctive remedies or urgent legal relief in any jurisdiction.
110 |
111 |
112 |
113 | 14. NO ASSIGNMENT. This license and your rights and obligations thereunder may not be assigned by you by any means or operation of law without NVIDIA’s permission. Any attempted assignment not approved by NVIDIA in writing shall be void and of no effect. NVIDIA may assign, delegate or transfer this license and its rights and obligations, and if to a non-affiliate you will be notified.
114 |
115 |
116 |
117 | 15. EXPORT. The SOFTWARE is subject to United States export laws and regulations. You agree to comply with all applicable U.S. and international export laws, including the Export Administration Regulations (EAR) administered by the U.S. Department of Commerce and economic sanctions administered by the U.S. Department of Treasury’s Office of Foreign Assets Control (OFAC). These laws include restrictions on destinations, end-users and end-use. By accepting this license, you confirm that you are not currently residing in a country or region currently embargoed by the U.S. and that you are not otherwise prohibited from receiving the SOFTWARE.
118 |
119 |
120 |
121 | 16. GOVERNMENT USE. The SOFTWARE is, and shall be treated as being, “Commercial Items” as that term is defined at 48 CFR § 2.101, consisting of “commercial computer software” and “commercial computer software documentation”, respectively, as such terms are used in, respectively, 48 CFR § 12.212 and 48 CFR §§ 227.7202 & 252.227-7014(a)(1). Use, duplication or disclosure by the U.S. Government or a U.S. Government subcontractor is subject to the restrictions in this license pursuant to 48 CFR § 12.212 or 48 CFR § 227.7202. In no event shall the US Government user acquire rights in the SOFTWARE beyond those specified in 48 C.F.R. 52.227-19(b)(1)-(2).
122 |
123 |
124 |
125 | 17. NOTICES. Please direct your legal notices or other correspondence to NVIDIA Corporation, 2788 San Tomas Expressway, Santa Clara, California 95051, United States of America, Attention: Legal Department.
126 |
127 |
128 |
129 | 18. ENTIRE AGREEMENT. This license is the final, complete and exclusive agreement between the parties relating to the subject matter of this license and supersedes all prior or contemporaneous understandings and agreements relating to this subject matter, whether oral or written. If any court of competent jurisdiction determines that any provision of this license is illegal, invalid or unenforceable, the remaining provisions will remain in full force and effect. Any amendment or waiver under this license shall be in writing and signed by representatives of both parties.
130 |
131 |
132 |
133 | (v. March 20, 2025)
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # PyCuVSLAM
2 |
3 | PyCuVSLAM is the official Python wrapper around the cuVSLAM visual-inertial SLAM (Simultaneous Localization And Mapping)
4 | software package developed by NVIDIA. It is a highly accurate and computationally efficient package
5 | using CUDA acceleration for real-time visual-inertial SLAM.
6 |
7 | 
8 |
9 | ## System Requirements
10 |
11 | PyCuVSLAM is supported on the following OS and platforms, with the system requirements and installation methods listed below:
12 |
13 | | OS | Architecture | System Requirements | Supported Installation Method |
14 | |-----------------------------------|--------------|----------------------------------------------|-------------------------------------------------|
15 | | Ubuntu 22.04 (Desktop/Laptop) | x86_64 | Python 3.10, Nvidia GPU with CUDA 12.6 | [Native][3], [Venv][4], [Conda][5], [Docker][6] |
16 | | Ubuntu 24.04 (Desktop/Laptop) | x86_64 | Nvidia GPU with CUDA 12.6 | [Conda][5], [Docker][6] |
17 | | Ubuntu 22.04 ([Nvidia Jetson][1]) | aarch64 | [Jetpack 6.1/6.2][2], Python 3.10, CUDA 12.6 | [Native][3], [Venv][4], [Conda][5], [Docker][6] |
18 |
19 | [1]: https://www.nvidia.com/en-us/autonomous-machines/embedded-systems/
20 | [2]: https://docs.nvidia.com/jetson/archives/jetpack-archived/jetpack-62/
21 | [3]: #option-1-native-install
22 | [4]: #option-2-using-venv
23 | [5]: #option-3-using-conda
24 | [6]: #option-4-using-docker
25 |
26 |
27 | ### CUDA Toolkit
28 | Make sure you have the CUDA Toolkit installed, you can download the toolkit from the [NVIDIA website](https://developer.nvidia.com/cuda-downloads). If you install the CUDA toolkit for the first time, make sure to restart your computer.
29 |
30 | ## Install Options
31 | Depending on your OS and platform and the supported installation method, follow the instructions below to install PyCuVSLAM.
32 |
33 | ### Option 1: Native Install
34 | **Important**: This option is only available for Ubuntu 22.04 x86_64 and Jetpack 6.1/6.2 aarch64.
35 |
36 | There are no special instructions for native install, proceed to [PyCuVSLAM installation](#pycuvslam-installation).
37 |
38 | ### Option 2: Using Venv
39 | **Important**: This option is only available for Ubuntu 22.04 x86_64 and Jetpack 6.1/6.2 aarch64.
40 |
41 | Create a virtual environment:
42 |
43 | ```bash
44 | python3 -m venv .venv
45 | source .venv/bin/activate
46 | ```
47 |
48 | When done using PyCuVSLAM, to deactivate the virtual environment, run `deactivate`.
49 |
50 | Proceed to [PyCuVSLAM installation](#pycuvslam-installation).
51 |
52 | ### Option 3: Using Conda
53 |
54 | **Important**: This option has been tested on Ubuntu 22.04 x86_64 and Ubuntu 24.04 x86_64. It *may* work on other
55 | versions of Ubuntu x86_64, but it has not been tested.
56 |
57 | Create a conda environment and install the required packages:
58 |
59 | ```bash
60 | conda create -n pycuvslam python==3.10 pip
61 | conda activate pycuvslam
62 | conda install -c conda-forge libstdcxx-ng=12.2.0
63 | export LD_LIBRARY_PATH=$CONDA_PREFIX/lib:$LD_LIBRARY_PATH
64 | ```
65 | **Important**: The `LD_LIBRARY_PATH` environment variable must be set every time you activate the
66 | conda environment to ensure that the correct `libpython` library is loaded.
67 |
68 | To deactivate the conda environment when you are done using PyCuVSLAM, run `conda deactivate`.
69 |
70 | Proceed to [PyCuVSLAM installation](#pycuvslam-installation).
71 |
72 | ### Option 4: Using Docker
73 | 1. Setup ngc
74 | ```bash
75 | docker login nvcr.io --username '$oauthtoken'
76 | ```
77 | For password enter key for ngc catalog from: https://org.ngc.nvidia.com/setup/api-keys
78 |
79 | 2. Build docker image
80 | ```bash
81 | git clone https://github.com/NVlabs/pycuvslam.git
82 | cd pycuvslam
83 | docker build . --network host --tag pycuvslam
84 | ```
85 |
86 | 3. Run container from image, and install cuvslam
87 | ```bash
88 | ./run_docker.sh
89 | ```
90 | To exit the container when you are done using the container, run `exit`.
91 |
92 | Proceed to step 2 of [PyCuVSLAM installation](#pycuvslam-installation).
93 |
94 | ## PyCuVSLAM Installation
95 |
96 | 1. Clone the PyCuVSLAM repository.
97 | ```bash
98 | git clone https://github.com/NVlabs/pycuvslam.git
99 | cd pycuvslam
100 | ```
101 |
102 | 2. Install the PyCuVSLAM package.
103 | ```bash
104 | pip install -e cuvslam/x86
105 | ```
106 | For Jetson, use the following command:
107 | ```bash
108 | pip install -e cuvslam/aarch64
109 | ```
110 |
111 | ## Run Examples
112 | 1. Install PyCuVSLAM using one of the installation methods mentioned above, and then install the
113 | required packages for the examples:
114 | ```bash
115 | pip install -r examples/requirements.txt
116 | ```
117 | 2. Run the examples:
118 | - [EuRoC Dataset Tutorial](docs/tutorial_euroc.md)
119 | - [KITTI Dataset Tutorial](docs/tutorial_kitti.md)
120 | - [Multi-Camera Dataset Tutorial](docs/tutorial_multicamera_edex.md)
121 | - [OAK-D Camera Tutorial](docs/tutorial_oakd.md)
122 | - [RealSense Camera Tutorial](docs/tutorial_realsense.md)
123 |
124 | ## API Documentation
125 |
126 | For detailed API documentation, please refer to the [API Documentation](https://nvlabs.github.io/PyCuVSLAM/api.html) page.
127 |
128 | ## Notes about SLAM performance
129 | The accuracy and robustness of a SLAM system can be effected by many different factors, here is a small list of some of these factors:
130 |
131 | - Intrinsics and extrinsics calibration accuracy are crucially important. Make sure your calibration is accurate. If you've never calibrated before, work with an experienced vendor to have your setup calibrated.
132 | - Synchronization and time stamping will make a huge difference to the performance of cuVSLAM. Make sure that your multi-camera images are captured at the same exact time, preferably through hardware synchronization, and that the relative timestamps of the captured images are correct across different cameras.
133 | - Frame rate can effect performance significantly. The ideal frame rate depends on your translational and rotational velocity. 30 FPS should work for most "human speed" movement.
134 | - Resolution is important. Minimum of 720p is recommended. cuVSLAM can operate on relatively high resolution image streams efficiently due to its CUDA acceleration.
135 | - Image quality is also very important. Make sure you have good lenses, exposure and white balancing that does not clip large parts of the image, and clean the dirt from your lenses. Motion blur can cause issues so make sure your exposure time is short enough to avoid motion blur. If your images are too dark, increase lighting in your environment.
136 | - Compute can effect your SLAM performance. If cuVSLAM does not have enough compute to keep up with the image streams, performance might degrade.
137 |
138 | ## Issues
139 |
140 | ### Issues pip installing PyCuVSLAM
141 |
142 | If you're having issues ```pip install```ing PyCuVSLAM because of lack of permission, try updating your pip:
143 |
144 | ```bash
145 | python -m pip install -U pip
146 | ```
147 |
148 | ### Reporting other issues
149 | Are you having problems running PyCuVSLAM? Do you have any suggestions? We'd love to hear your feedback in the [issues](https://github.com/NVlabs/pycuvslam/issues) tab.
150 |
151 | ## ROS2 Support
152 |
153 | If you would like to use cuVSLAM in a ROS2 environment, please refer to the following links:
154 | * [Isaac ROS cuVSLAM GitHub](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_visual_slam)
155 | * [Isaac ROS cuVSLAM Documentation](https://nvidia-isaac-ros.github.io/concepts/visual_slam/cuvslam/index.html)
156 | * [Isaac ROS cuVSLAM User Manual](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_visual_slam/isaac_ros_visual_slam/index.html)
157 |
158 |
159 | ## License
160 | This project is licensed under a non-commercial NVIDIA license, for details refer to the [LICENCE](LICENSE) file.
161 |
--------------------------------------------------------------------------------
/cuvslam/aarch64/cuvslam/__init__.py:
--------------------------------------------------------------------------------
1 | """CUVSLAM Python bindings."""
2 |
3 | from .pycuvslam import *
4 |
5 | __version__ = "0.1.0"
--------------------------------------------------------------------------------
/cuvslam/aarch64/cuvslam/cuvslam.pyi:
--------------------------------------------------------------------------------
1 | from typing import Dict, List, Optional, Tuple, Union, Sequence, overload
2 | import numpy as np
3 | import numpy.typing as npt
4 |
5 |
6 | # Enum definitions
7 |
8 | class DistortionModel:
9 | Pinhole: int
10 | Brown: int
11 | Fisheye: int
12 | Polynomial: int
13 |
14 |
15 | class TrackerMulticameraMode:
16 | Performance: int
17 | Precision: int
18 | Moderate: int
19 |
20 |
21 | class TrackerOdometryMode:
22 | Multicamera: int
23 | Inertial: int
24 | Mono: int
25 |
26 |
27 | # Main classes
28 |
29 | class Pose:
30 | rotation: Union[List[float], npt.NDArray[np.float32]] # shape (4,)
31 | translation: Union[List[float], npt.NDArray[np.float32]] # shape (3,)
32 |
33 | @overload
34 | def __init__(self) -> None: ...
35 |
36 | @overload
37 | def __init__(self, rotation: Union[Sequence[float], npt.NDArray[np.float32]],
38 | translation: Union[Sequence[float], npt.NDArray[np.float32]]) -> None: ...
39 |
40 | def __str__(self) -> str: ...
41 | def __repr__(self) -> str: ...
42 |
43 |
44 | class Distortion:
45 | model: Union[DistortionModel, int]
46 | parameters: Sequence[float]
47 |
48 | @overload
49 | def __init__(self) -> None: ...
50 |
51 | @overload
52 | def __init__(self, model: Union[DistortionModel, int],
53 | parameters: Sequence[float] = ...) -> None: ...
54 |
55 | def __str__(self) -> str: ...
56 | def __repr__(self) -> str: ...
57 |
58 |
59 | class Camera:
60 | size: Union[List[int], npt.NDArray[np.int32]] # shape (2,)
61 | principal: Union[List[float], npt.NDArray[np.float32]] # shape (2,)
62 | focal: Union[List[float], npt.NDArray[np.float32]] # shape (2,)
63 | rig_from_camera: Pose
64 | distortion: Distortion
65 | border_top: int
66 | border_bottom: int
67 | border_left: int
68 | border_right: int
69 |
70 | @overload
71 | def __init__(self) -> None: ...
72 |
73 | @overload
74 | def __init__(
75 | self,
76 | *,
77 | size: Union[Sequence[int], npt.NDArray[np.int32]],
78 | principal: Union[Sequence[float], npt.NDArray[np.float32]],
79 | focal: Union[Sequence[float], npt.NDArray[np.float32]],
80 | rig_from_camera: Pose = ...,
81 | distortion: Distortion = ...,
82 | border_top: int = 0,
83 | border_bottom: int = 0,
84 | border_left: int = 0,
85 | border_right: int = 0
86 | ) -> None: ...
87 | def __str__(self) -> str: ...
88 | def __repr__(self) -> str: ...
89 |
90 |
91 | class ImuCalibration:
92 | rig_from_imu: Pose
93 | gyroscope_noise_density: float
94 | accelerometer_noise_density: float
95 | gyroscope_random_walk: float
96 | accelerometer_random_walk: float
97 | frequency: float
98 |
99 | def __init__(self) -> None: ...
100 | def __repr__(self) -> str: ...
101 |
102 |
103 | class Rig:
104 | cameras: List[Camera]
105 | imus: List[ImuCalibration]
106 |
107 | def __init__(
108 | self,
109 | cameras: List[Camera] = ...,
110 | imus: List[ImuCalibration] = ...
111 | ) -> None: ...
112 | def __repr__(self) -> str: ...
113 |
114 |
115 | class PoseEstimate:
116 | timestamp_ns: int
117 | is_valid: bool
118 | pose: Pose
119 |
120 | def __init__(self) -> None: ...
121 | def __repr__(self) -> str: ...
122 |
123 |
124 | class Observation:
125 | id: int
126 | u: float
127 | v: float
128 | camera_index: int
129 |
130 | def __init__(self) -> None: ...
131 | def __repr__(self) -> str: ...
132 |
133 |
134 | class Landmark:
135 | id: int
136 | coords: Union[Sequence[float], List[float]] # length 3, x,y,z coordinates
137 |
138 | def __init__(self) -> None: ...
139 | def __repr__(self) -> str: ...
140 |
141 |
142 | class ImuMeasurement:
143 | timestamp_ns: int
144 | linear_accelerations: Union[Sequence[float], npt.NDArray[np.float32]]
145 | angular_velocities: Union[Sequence[float], npt.NDArray[np.float32]]
146 |
147 | def __init__(self) -> None: ...
148 | def __repr__(self) -> str: ...
149 |
150 |
151 | # Tracker related classes
152 |
153 | class TrackerConfig:
154 | multicam_mode: Union[TrackerMulticameraMode, int]
155 | odometry_mode: Union[TrackerOdometryMode, int]
156 | use_gpu: bool
157 | async_sba: bool
158 | use_motion_model: bool
159 | use_denoising: bool
160 | horizontal_stereo_camera: bool
161 | enable_observations_export: bool
162 | enable_landmarks_export: bool
163 | enable_final_landmarks_export: bool
164 | max_frame_delta_s: float
165 | debug_dump_directory: str
166 | debug_imu_mode: bool
167 | def __init__(
168 | self,
169 | *,
170 | multicam_mode: Union[TrackerMulticameraMode, int] = ...,
171 | odometry_mode: Union[TrackerOdometryMode, int] = ...,
172 | use_gpu: bool = ...,
173 | async_sba: bool = ...,
174 | use_motion_model: bool = ...,
175 | use_denoising: bool = ...,
176 | horizontal_stereo_camera: bool = ...,
177 | enable_observations_export: bool = ...,
178 | enable_landmarks_export: bool = ...,
179 | enable_final_landmarks_export: bool = ...,
180 | max_frame_delta_s: float = ...,
181 | debug_dump_directory: str = ...,
182 | debug_imu_mode: bool = ...
183 | ) -> None: ...
184 |
185 |
186 | class Tracker:
187 | def __init__(self, rig: Rig, cfg: TrackerConfig = ...) -> None: ...
188 |
189 | def track(
190 | self,
191 | timestamp: int,
192 | images: List[npt.NDArray[np.uint8]],
193 | masks: Optional[List[npt.NDArray[np.uint8]]] = None
194 | ) -> PoseEstimate: ...
195 |
196 | def register_imu_measurement(
197 | self,
198 | sensor_index: int,
199 | imu_measurement: ImuMeasurement
200 | ) -> None: ...
201 |
202 | def get_last_observations(
203 | self,
204 | camera_index: int
205 | ) -> List[Observation]: ...
206 | def get_last_landmarks(self) -> List[Landmark]: ...
207 | def get_last_gravity(self) -> Optional[npt.NDArray[np.float32]]: ...
208 | def get_final_landmarks(self) -> Dict[int, npt.NDArray[np.float32]]: ...
209 |
210 |
211 | # Free functions
212 |
213 | def get_version() -> Tuple[bool, int, int]: ...
214 | def set_verbosity(verbosity: int) -> None: ...
215 | def warm_up_gpu() -> None: ...
216 |
--------------------------------------------------------------------------------
/cuvslam/aarch64/cuvslam/libcuvslam.so:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:40e279ec1cb1844ae45b83b16c5ff3829dd0e8c528239f23ad4a04dc162e0e77
3 | size 15887920
4 |
--------------------------------------------------------------------------------
/cuvslam/aarch64/cuvslam/pycuvslam.so:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:c1fc6033d75a6b04a34bb920ec5510acd54b56ddcd7c05102395c02c254763d0
3 | size 5007640
4 |
--------------------------------------------------------------------------------
/cuvslam/aarch64/pyproject.toml:
--------------------------------------------------------------------------------
1 | [build-system]
2 | requires = ["setuptools>=42", "wheel"]
3 | build-backend = "setuptools.build_meta"
4 |
5 | [project]
6 | name = "cuvslam"
7 | version = "0.1.0"
8 | description = "Python bindings for CUVSLAM library"
9 | requires-python = "==3.10.*"
10 | urls = {Homepage = "https://github.com/NVlabs/pycuvslam"}
11 | classifiers = [
12 | "Operating System :: POSIX :: Linux",
13 | "Programming Language :: Python :: 3.10",
14 | "Environment :: GPU :: NVIDIA CUDA",
15 | ]
16 | dependencies = [
17 | "nvidia-cuda-runtime-cu12>=12.0; sys_platform == 'linux'"
18 | ]
19 |
20 | [tool.setuptools]
21 | packages = ["cuvslam"]
22 | package-data = {"cuvslam" = ["*.so"]}
23 |
--------------------------------------------------------------------------------
/cuvslam/aarch64/setup.py:
--------------------------------------------------------------------------------
1 | from setuptools import setup
2 |
3 | setup()
4 |
--------------------------------------------------------------------------------
/cuvslam/x86/cuvslam/__init__.py:
--------------------------------------------------------------------------------
1 | """CUVSLAM Python bindings."""
2 |
3 | from .pycuvslam import *
4 |
5 | __version__ = "0.1.0"
--------------------------------------------------------------------------------
/cuvslam/x86/cuvslam/cuvslam.pyi:
--------------------------------------------------------------------------------
1 | from typing import Dict, List, Optional, Tuple, Union, Sequence, overload
2 | import numpy as np
3 | import numpy.typing as npt
4 |
5 |
6 | # Enum definitions
7 |
8 | class DistortionModel:
9 | Pinhole: int
10 | Brown: int
11 | Fisheye: int
12 | Polynomial: int
13 |
14 |
15 | class TrackerMulticameraMode:
16 | Performance: int
17 | Precision: int
18 | Moderate: int
19 |
20 |
21 | class TrackerOdometryMode:
22 | Multicamera: int
23 | Inertial: int
24 | Mono: int
25 |
26 |
27 | # Main classes
28 |
29 | class Pose:
30 | rotation: Union[List[float], npt.NDArray[np.float32]] # shape (4,)
31 | translation: Union[List[float], npt.NDArray[np.float32]] # shape (3,)
32 |
33 | @overload
34 | def __init__(self) -> None: ...
35 |
36 | @overload
37 | def __init__(self, rotation: Union[Sequence[float], npt.NDArray[np.float32]],
38 | translation: Union[Sequence[float], npt.NDArray[np.float32]]) -> None: ...
39 |
40 | def __str__(self) -> str: ...
41 | def __repr__(self) -> str: ...
42 |
43 |
44 | class Distortion:
45 | model: Union[DistortionModel, int]
46 | parameters: Sequence[float]
47 |
48 | @overload
49 | def __init__(self) -> None: ...
50 |
51 | @overload
52 | def __init__(self, model: Union[DistortionModel, int],
53 | parameters: Sequence[float] = ...) -> None: ...
54 |
55 | def __str__(self) -> str: ...
56 | def __repr__(self) -> str: ...
57 |
58 |
59 | class Camera:
60 | size: Union[List[int], npt.NDArray[np.int32]] # shape (2,)
61 | principal: Union[List[float], npt.NDArray[np.float32]] # shape (2,)
62 | focal: Union[List[float], npt.NDArray[np.float32]] # shape (2,)
63 | rig_from_camera: Pose
64 | distortion: Distortion
65 | border_top: int
66 | border_bottom: int
67 | border_left: int
68 | border_right: int
69 |
70 | @overload
71 | def __init__(self) -> None: ...
72 |
73 | @overload
74 | def __init__(
75 | self,
76 | *,
77 | size: Union[Sequence[int], npt.NDArray[np.int32]],
78 | principal: Union[Sequence[float], npt.NDArray[np.float32]],
79 | focal: Union[Sequence[float], npt.NDArray[np.float32]],
80 | rig_from_camera: Pose = ...,
81 | distortion: Distortion = ...,
82 | border_top: int = 0,
83 | border_bottom: int = 0,
84 | border_left: int = 0,
85 | border_right: int = 0
86 | ) -> None: ...
87 | def __str__(self) -> str: ...
88 | def __repr__(self) -> str: ...
89 |
90 |
91 | class ImuCalibration:
92 | rig_from_imu: Pose
93 | gyroscope_noise_density: float
94 | accelerometer_noise_density: float
95 | gyroscope_random_walk: float
96 | accelerometer_random_walk: float
97 | frequency: float
98 |
99 | def __init__(self) -> None: ...
100 | def __repr__(self) -> str: ...
101 |
102 |
103 | class Rig:
104 | cameras: List[Camera]
105 | imus: List[ImuCalibration]
106 |
107 | def __init__(
108 | self,
109 | cameras: List[Camera] = ...,
110 | imus: List[ImuCalibration] = ...
111 | ) -> None: ...
112 | def __repr__(self) -> str: ...
113 |
114 |
115 | class PoseEstimate:
116 | timestamp_ns: int
117 | is_valid: bool
118 | pose: Pose
119 |
120 | def __init__(self) -> None: ...
121 | def __repr__(self) -> str: ...
122 |
123 |
124 | class Observation:
125 | id: int
126 | u: float
127 | v: float
128 | camera_index: int
129 |
130 | def __init__(self) -> None: ...
131 | def __repr__(self) -> str: ...
132 |
133 |
134 | class Landmark:
135 | id: int
136 | coords: Union[Sequence[float], List[float]] # length 3, x,y,z coordinates
137 |
138 | def __init__(self) -> None: ...
139 | def __repr__(self) -> str: ...
140 |
141 |
142 | class ImuMeasurement:
143 | timestamp_ns: int
144 | linear_accelerations: Union[Sequence[float], npt.NDArray[np.float32]]
145 | angular_velocities: Union[Sequence[float], npt.NDArray[np.float32]]
146 |
147 | def __init__(self) -> None: ...
148 | def __repr__(self) -> str: ...
149 |
150 |
151 | # Tracker related classes
152 |
153 | class TrackerConfig:
154 | multicam_mode: Union[TrackerMulticameraMode, int]
155 | odometry_mode: Union[TrackerOdometryMode, int]
156 | use_gpu: bool
157 | async_sba: bool
158 | use_motion_model: bool
159 | use_denoising: bool
160 | horizontal_stereo_camera: bool
161 | enable_observations_export: bool
162 | enable_landmarks_export: bool
163 | enable_final_landmarks_export: bool
164 | max_frame_delta_s: float
165 | debug_dump_directory: str
166 | debug_imu_mode: bool
167 | def __init__(
168 | self,
169 | *,
170 | multicam_mode: Union[TrackerMulticameraMode, int] = ...,
171 | odometry_mode: Union[TrackerOdometryMode, int] = ...,
172 | use_gpu: bool = ...,
173 | async_sba: bool = ...,
174 | use_motion_model: bool = ...,
175 | use_denoising: bool = ...,
176 | horizontal_stereo_camera: bool = ...,
177 | enable_observations_export: bool = ...,
178 | enable_landmarks_export: bool = ...,
179 | enable_final_landmarks_export: bool = ...,
180 | max_frame_delta_s: float = ...,
181 | debug_dump_directory: str = ...,
182 | debug_imu_mode: bool = ...
183 | ) -> None: ...
184 |
185 |
186 | class Tracker:
187 | def __init__(self, rig: Rig, cfg: TrackerConfig = ...) -> None: ...
188 |
189 | def track(
190 | self,
191 | timestamp: int,
192 | images: List[npt.NDArray[np.uint8]],
193 | masks: Optional[List[npt.NDArray[np.uint8]]] = None
194 | ) -> PoseEstimate: ...
195 |
196 | def register_imu_measurement(
197 | self,
198 | sensor_index: int,
199 | imu_measurement: ImuMeasurement
200 | ) -> None: ...
201 |
202 | def get_last_observations(
203 | self,
204 | camera_index: int
205 | ) -> List[Observation]: ...
206 | def get_last_landmarks(self) -> List[Landmark]: ...
207 | def get_last_gravity(self) -> Optional[npt.NDArray[np.float32]]: ...
208 | def get_final_landmarks(self) -> Dict[int, npt.NDArray[np.float32]]: ...
209 |
210 |
211 | # Free functions
212 |
213 | def get_version() -> Tuple[bool, int, int]: ...
214 | def set_verbosity(verbosity: int) -> None: ...
215 | def warm_up_gpu() -> None: ...
216 |
--------------------------------------------------------------------------------
/cuvslam/x86/cuvslam/libcuvslam.so:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:c006231165ebeef49559657f4c7237b3b83782da369a509b8f7c2406cd560c61
3 | size 16551560
4 |
--------------------------------------------------------------------------------
/cuvslam/x86/cuvslam/pycuvslam.so:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:55b3b572ee5f829f957ff71f8ff1b30483a16ff0215f3401f47b5f85f9b7e949
3 | size 5769544
4 |
--------------------------------------------------------------------------------
/cuvslam/x86/pyproject.toml:
--------------------------------------------------------------------------------
1 | [build-system]
2 | requires = ["setuptools>=42", "wheel"]
3 | build-backend = "setuptools.build_meta"
4 |
5 | [project]
6 | name = "cuvslam"
7 | version = "0.1.0"
8 | description = "Python bindings for CUVSLAM library"
9 | requires-python = "==3.10.*"
10 | urls = {Homepage = "https://github.com/NVlabs/pycuvslam"}
11 | classifiers = [
12 | "Operating System :: POSIX :: Linux",
13 | "Programming Language :: Python :: 3.10",
14 | "Environment :: GPU :: NVIDIA CUDA",
15 | ]
16 | dependencies = [
17 | "nvidia-cuda-runtime-cu12>=12.0; sys_platform == 'linux'"
18 | ]
19 |
20 | [tool.setuptools]
21 | packages = ["cuvslam"]
22 | package-data = {"cuvslam" = ["*.so"]}
23 |
--------------------------------------------------------------------------------
/cuvslam/x86/setup.py:
--------------------------------------------------------------------------------
1 | from setuptools import setup
2 |
3 | setup()
4 |
--------------------------------------------------------------------------------
/docs/README.md:
--------------------------------------------------------------------------------
1 | ## API Documentation
2 |
3 | For detailed API documentation, please refer to the [API Documentation](https://nvlabs.github.io/PyCuVSLAM/api.html) page.
4 |
5 | ## Tutorials
6 |
7 | If you'd like to see how the PyCuVSLAM API is used in a real-world example, take a look at the following tutorials:
8 |
9 | - [EuRoC Dataset Tutorial](tutorial_euroc.md)
10 | - [KITTI Dataset Tutorial](tutorial_kitti.md)
11 | - [Multi-Camera Dataset Tutorial](tutorial_multicamera_edex.md)
12 | - [OAK-D Camera Tutorial](tutorial_oakd.md)
13 | - [RealSense Camera Tutorial](tutorial_realsense.md)
14 |
--------------------------------------------------------------------------------
/docs/tutorial_euroc.jpg:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:3154eb4f515f386a9c6f3f895ea48d2b481e03b269c8a3b63d849fad4cdbd333
3 | size 1064156
4 |
--------------------------------------------------------------------------------
/docs/tutorial_euroc.md:
--------------------------------------------------------------------------------
1 | # Tutorial: Running PyCuVSLAM on the EuRoC MAV dataset
2 |
3 | This tutorial demonstrates how to use PyCuVSLAM with the EuRoC MAV dataset.
4 |
5 | ## System Requirements
6 | Before going to the next step, make sure you've setup your system to support PyCuVSLAM: [System Requirements](https://gitlab-master.nvidia.com/elbrus/pycuvslam/-/tree/main#system-requirements)
7 |
8 | ## Dataset Setup
9 |
10 | 1. Download the EuRoC MH_01_easy dataset:
11 |
12 | ```bash
13 | wget http://robotics.ethz.ch/~asl-datasets/ijrr_euroc_mav_dataset/machine_hall/MH_01_easy/MH_01_easy.zip -O examples/euroc/dataset/MH_01_easy.zip
14 | unzip examples/euroc/dataset/MH_01_easy.zip -d examples/euroc/dataset
15 | rm examples/euroc/dataset/MH_01_easy.zip
16 | ```
17 |
18 | 2. Copy the calibration files:
19 |
20 | ```bash
21 | cp examples/euroc/dataset/sensor_cam0.yaml examples/euroc/dataset/mav0/cam0/sensor_recalibrated.yaml
22 | cp examples/euroc/dataset/sensor_cam1.yaml examples/euroc/dataset/mav0/cam1/sensor_recalibrated.yaml
23 | cp examples/euroc/dataset/sensor_imu0.yaml examples/euroc/dataset/mav0/imu0/sensor_recalibrated.yaml
24 | ```
25 |
26 | > **Note**: We provide recalibrated camera and IMU parameters to improve tracking accuracy. We strongly recommend using these calibration files instead of the original ones provided with the dataset.
27 |
28 | ## Running PyCuVSLAM
29 |
30 | Execute the following command to start tracking on EuRoC:
31 |
32 | ```bash
33 | python3 examples/euroc/track_euroc.py
34 | ```
35 |
36 | ### Available Modes
37 |
38 | To change tracking mode, modify this line in `track_euroc.py`:
39 | ```python
40 | # Available tracking modes:
41 | # vslam.TrackerOdometryMode.Mono - Monocular visual odometry
42 | # vslam.TrackerOdometryMode.Multicamera - Stereo visual odometry
43 | # vslam.TrackerOdometryMode.Inertial - Visual-inertial odometry
44 | euroc_tracking_mode = vslam.TrackerOdometryMode.Mono # Change this line for desired mode
45 | ```
46 |
47 | ## Visualization
48 |
49 | The real-time visualization shows:
50 | - Camera trajectory
51 | - Feature tracking
52 | - Gravity vector (in inertial mode)
53 |
54 | 
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
--------------------------------------------------------------------------------
/docs/tutorial_kitti.jpg:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:e7605b5ea000b1b0f55879736846e33faaefab5a250c7eb801bdca39a950e8cd
3 | size 330789
4 |
--------------------------------------------------------------------------------
/docs/tutorial_kitti.md:
--------------------------------------------------------------------------------
1 | # Tutorial: Running PyCuVSLAM Stereo Visual Odometry on the KITTI dataset
2 |
3 | The KITTI Vision Benchmark Suite is a high-quality dataset benchmarking and comparing various computer vision algorithms.
4 | Among other options, the KITTI dataset has sequences for evaluating stereo-visual odometry.
5 |
6 | ## System Requirements
7 | Before going to the next step, make sure you've setup your system to support PyCuVSLAM: [System Requirements](https://gitlab-master.nvidia.com/elbrus/pycuvslam/-/tree/main#system-requirements)
8 |
9 |
10 | ## Dataset Setup
11 |
12 | 1. To get the KITTI test sequences, download
13 | [the odometry data set](http://www.cvlibs.net/datasets/kitti/eval_odometry.php) (grayscale, 22 GB).
14 | You will have to register for an account. Once you do, you will receive a download link to the `data_odometry_gray.zip` file.
15 |
16 | 2. Unpack it to your dataset folder.
17 |
18 | ```bash
19 | unzip data_odometry_gray.zip -d examples/kitti
20 | ```
21 |
22 | When you unpack it, you get the
23 | following structure:
24 | ```
25 | dataset_odometry_gray
26 | dataset -> should be mapped or placed in examples/kitti/dataset
27 | sequences
28 | 00
29 | image_0
30 | 000000.png
31 | ...
32 | 004550.png
33 | image_1
34 | 000000.png
35 | ...
36 | 004550.png
37 | calib.txt
38 | times.txt
39 | 01
40 | ...
41 | ```
42 | Each of the 20 folders has a stereo sequence and calibration of cameras.
43 |
44 | ## Running PyCuVSLAM
45 |
46 | Execute the following command to start tracking on KITTI:
47 |
48 | ```bash
49 | python3 examples/kitti/track_kitti.py
50 | ```
51 |
52 | ## Visualization
53 |
54 | The visualization will look something like this:
55 |
56 | 
57 |
--------------------------------------------------------------------------------
/docs/tutorial_multicamera_edex.gif:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:532741cf4fce88a90e40d986d83d09755d2fbf74a70db9db338183086e6edf69
3 | size 26734862
4 |
--------------------------------------------------------------------------------
/docs/tutorial_multicamera_edex.md:
--------------------------------------------------------------------------------
1 | # Tutorial: Running PyCuVSlam Multicamera Visual Odometry on the R2B Galileo dataset
2 |
3 | cuVSLAM could be run in multicamera mode on rig with HW-syncronized stereo cameras. This example is based on original tutorial provided for ROSbag in [ISAAC ROS dicumentation](https://nvidia-isaac-ros.github.io/concepts/visual_slam/cuvslam/tutorial_multi_hawk.html)
4 |
5 | ## Get dataset
6 | To get the multicamera datasets you need to download [r2b datasets in ROSbag format](https://registry.ngc.nvidia.com/orgs/nvidia/teams/isaac/resources/r2bdataset2024/files) and convert it using [edex extractor](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_common/isaac_ros_rosbag_utils/index.html#edex-extraction)
7 |
8 | 1. Follow the original [ISAAC ROS Multi-camera Visual SLAM tutorial](https://nvidia-isaac-ros.github.io/concepts/visual_slam/cuvslam/tutorial_multi_hawk.html) of execution on a rosbag. Make sure, that rosbag file has been downloaded and you are able to play it within docker container:
9 |
10 | ```bash
11 | ros2 bag play ${ISAAC_ROS_WS}/isaac_ros_assets/rosbags/r2b_galileo
12 | ```
13 |
14 | 2. Set up [Isaac ROS rosbag utils](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_common/isaac_ros_rosbag_utils/index.html) package and run within docker container:
15 |
16 | ```bash
17 | ros2 run isaac_ros_rosbag_utils extract_edex --config_path src/isaac_ros_common/isaac_ros_rosbag_utils/config/edex_extraction_nova.yaml --rosbag_path ${ISAAC_ROS_WS}/isaac_ros_assets/rosbags/r2b_galileo --edex_path ${ISAAC_ROS_WS}/isaac_ros_assets/r2b_galileo_edex
18 | ```
19 |
20 | The expected stucture of output folder:
21 | ```bash
22 | r2b_galileo_edex
23 | ├── frame_metadata.jsonl
24 | ├── images
25 | │ ├── back_stereo_camera
26 | │ │ ├── left
27 | │ │ │ ├── 000000.png
28 | │ │ │ ├── 000001.png
29 | │ │ │ ├── 000002.png
30 | │ │ │ ...
31 | │ │ └── right
32 | │ │ │ ├── 000000.png
33 | │ │ │ ├── 000001.png
34 | │ │ │ ├── 000002.png
35 | │ │ │ ...
36 | │ ├── front_stereo_camera
37 | │ │ ├── left
38 | │ │ │ ├── 000000.png
39 | │ │ │ ├── 000001.png
40 | │ │ │ ├── 000002.png
41 | │ │ │ ...
42 | │ │ └── right
43 | │ │ │ ├── 000000.png
44 | │ │ │ ├── 000001.png
45 | │ │ │ ├── 000002.png
46 | │ │ │ ...
47 | │ ├── left_stereo_camera
48 | │ │ ├── left
49 | │ │ │ ├── 000000.png
50 | │ │ │ ├── 000001.png
51 | │ │ │ ├── 000002.png
52 | │ │ │ ...
53 | │ │ └── right
54 | │ │ │ ├── 000000.png
55 | │ │ │ ├── 000001.png
56 | │ │ │ ├── 000002.png
57 | │ │ │ ...
58 | │ ├── raw_timestamps.csv
59 | │ ├── right_stereo_camera
60 | │ │ ├── left
61 | │ │ │ ├── 000000.png
62 | │ │ │ ├── 000001.png
63 | │ │ │ ├── 000002.png
64 | │ │ │ ...
65 | │ │ └── right
66 | │ │ │ ├── 000000.png
67 | │ │ │ ├── 000001.png
68 | │ │ │ ├── 000002.png
69 | │ │ │ ...
70 | │ └── synced_timestamps.csv
71 | ├── robot.urdf
72 | └── stereo.edex
73 | ```
74 |
75 | 3. Exit from docker container and move `r2b_galileo_edex` folder to multicamera example folder:
76 | ```bash
77 | mkdir -p ~/pycuvslam/examples/multicamera_edex/datasets
78 | mv ~/workspaces/isaac/isaac_ros_assets/r2b_galileo_edex ~/pycuvslam/examples/multicamera_edex/datasets/r2b_galileo_edex
79 | ```
80 |
81 | ## Setup test environment
82 |
83 | Setup cuVSLAM virtual environment based on [Installation Guide](../README.md#Installation-Guide)
84 |
85 | ## Run tracking and visualization
86 |
87 | Go to the `examples/multicamera_edex` folder and run
88 |
89 | ```bash
90 | python3 track_multicamera.py
91 | ```
92 |
93 | As a result, you will get rerun with fancy visualization:
94 |
95 | 
96 |
--------------------------------------------------------------------------------
/docs/tutorial_oakd.md:
--------------------------------------------------------------------------------
1 | # Tutorial: Running PyCuVSlam Stereo Visual Odometry on OAK-D Stereo Camera
2 |
3 | This tutorial shows how to run live pyCUVSLAM tracking on an OAK-D stereo camera that provides unrectified images
4 |
5 | ## Setting up the cuvslam environment
6 | Refer to the [Installation Guide](../README.md#Installation-Guide) for instructions on installing and configuring all required dependencies
7 |
8 | ## Setting up DepthAI
9 | 1. Install the [DepthAI Python library](https://github.com/luxonis/depthai-python) following the official documentation
10 | 2. Test your setup by running a basic [camera example](https://docs.luxonis.com/software/depthai/examples/rgb_preview/). Ensure it works correctly before proceeding
11 |
12 | ## Running Stereo Visual Odometry
13 |
14 | ```bash
15 | python3 examples/oak-d/run_stereo.py
16 | ```
17 |
18 | You should see the following interactive visualization in rerun:
19 | 
20 |
21 | Note: The pyCUVSLAM stereo tracker expects reliably synchronized stereo pairs with a stable FPS. If your camera pipeline is doing extensive on-device processing or AI inference, frame rates may drop, and image pairs may become unsynchronized. Watch for warnings about low FPS or mismatched stereo frames
22 |
23 | If you experience low FPS even in the basic setup, you can investigate potential bottlenecks using the supplied [measurement tools](https://docs.luxonis.com/software/depthai/optimizing/) for OAK devices
--------------------------------------------------------------------------------
/docs/tutorial_oakd_stereo.gif:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:d4befb8345270c9bcc2a69b9f275aeb7380abb42ae765925d6d1b423856b860b
3 | size 11827928
4 |
--------------------------------------------------------------------------------
/docs/tutorial_realsense.md:
--------------------------------------------------------------------------------
1 | # Tutorial: Running PycuVSLAM Stereo Visual Odometry on a Realsense Stereo Camera
2 |
3 | This tutorial walks you through how to operate live PycuVSLAM tracking on a Realsense stereo camera
4 |
5 | ## Set Up the pyCUVSLAM Environment
6 |
7 | Refer to the [Installation Guide](../README.md#Installation-Guide) for detailed environment setup instructions
8 |
9 | ## Setting Up librealsense
10 |
11 | The official [librealsense Python installation guide](https://github.com/IntelRealSense/librealsense/blob/master/wrappers/python/readme.md) is recommended. We highly suggest building both librealsense and its Python wrapper from source:
12 |
13 | 1. Follow the build instructions for the [librealsense library](https://github.com/IntelRealSense/librealsense/blob/master/doc/installation.md)
14 |
15 | 2. Compile librealsense2 with Python bindings:
16 | ```bash
17 | cmake ../ -DCMAKE_BUILD_TYPE=Release -DBUILD_EXAMPLES=true -DBUILD_PYTHON_BINDINGS=true -DPYTHON_EXECUTABLE=$(which python3.10)
18 |
19 | make -j
20 | ```
21 |
22 | 3. Once the build and installation are finished, add the build directory to your path:
23 | ```bash
24 | export PYTHONPATH=$PYTHONPATH:~/librealsense/build/Release
25 | ```
26 |
27 | 4. Test your setup by running a [simple camera example](https://github.com/IntelRealSense/librealsense/blob/master/wrappers/python/examples/opencv_viewer_example.py) to verify that everything was installed correctly
28 |
29 | ## Running Stereo Visual Odometry
30 |
31 | Go to the `examples/realsense` folder and run stereo visual odometry:
32 | ```bash
33 | python3 run_stereo.py
34 | ```
35 | You should see the following interactive visualization in rerun:
36 | 
37 |
38 | ## Running Stereo Inertial Odometry
39 |
40 | Stereo inertial odometry is only supported by Realsense stereo cameras equipped with an onboard IMU
41 |
42 |
43 | Note: Stereo Inertial Odometry relies heavily on accurate [IMU Noise Parameters](https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model). You should [calculate IMU noise parameters](https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model) for your specific camera and update the settings in [camera_utils.py](../examples/realsense/camera_utils.py) accordingly
44 |
45 | Run stereo visual inertial odometry:
46 | ```bash
47 | python3 run_vio.py
48 | ```
49 | After a brief moment, a gravity vector (indicated by the bold red line pointing downward) should appear in the 3D visualization window:
50 | 
--------------------------------------------------------------------------------
/docs/tutorial_realsense_stereo.gif:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:76aeb1b85b450f358caeb5371dbdd326109243cf9723d062573093d5d9bed673
3 | size 13184086
4 |
--------------------------------------------------------------------------------
/docs/tutorial_realsense_vio.gif:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:a5371df67eb5be3557cf5c34ba126532dcc13a0cdcb34d0f6a4367dfe1ed537c
3 | size 9611841
4 |
--------------------------------------------------------------------------------
/examples/euroc/dataset/sensor_cam0.yaml:
--------------------------------------------------------------------------------
1 | # General sensor definitions.
2 | sensor_type: camera
3 | comment: VI-Sensor cam0 (MT9M034)
4 |
5 | # Sensor extrinsics wrt. the cam0-frame.
6 | T_Cam0:
7 | cols: 4
8 | rows: 4
9 | data: [1.0, 0.0, 0.0, 0.0,
10 | 0.0, 1.0, 0.0, 0.0,
11 | 0.0, 0.0, 1.0, 0.0,
12 | 0.0, 0.0, 0.0, 1.0]
13 |
14 | # Camera specific definitions.
15 | rate_hz: 20
16 | resolution: [752, 480]
17 | camera_model: fisheye
18 | intrinsics: [460.9855047976205, 459.67892586299877, 366.09923470990486, 249.22157605207943] #fu, fv, cu, cv
19 | distortion_model: radial-tangential
20 | distortion_coefficients: [-0.0062748193357009315, 0.029005519692414498, -0.03438856012105873, 0.014830434499283266]
21 |
22 |
--------------------------------------------------------------------------------
/examples/euroc/dataset/sensor_cam1.yaml:
--------------------------------------------------------------------------------
1 | # General sensor definitions.
2 | sensor_type: camera
3 | comment: VI-Sensor cam0 (MT9M034)
4 |
5 | # Sensor extrinsics wrt. the cam0-frame.
6 | T_Cam0:
7 | cols: 4
8 | rows: 4
9 | data: [9.999967e-01, -2.188900e-03, 1.354800e-03, 1.099839e-01,
10 | 2.207800e-03, 9.998979e-01, -1.412050e-02, -5.322000e-04,
11 | -1.323700e-03, 1.412340e-02, 9.998994e-01, 4.407000e-04,
12 | 0.0, 0.0, 0.0, 1.0]
13 |
14 | # Camera specific definitions.
15 | rate_hz: 20
16 | resolution: [752, 480]
17 | camera_model: fisheye
18 | intrinsics: [459.56983030590357, 458.20957848757143, 379.5888918566419, 255.9525258537914] #fu, fv, cu, cv
19 | distortion_model: radial-tangential
20 | distortion_coefficients: [0.0030523152970989243, 0.0022729295767180894, -0.0023088086978921007, 0.002031411542915807]
21 |
22 |
--------------------------------------------------------------------------------
/examples/euroc/dataset/sensor_imu0.yaml:
--------------------------------------------------------------------------------
1 | #Default imu sensor yaml file
2 | sensor_type: imu
3 | comment: VI-Sensor IMU (ADIS16448)
4 |
5 | # Sensor extrinsics wrt. the cam0-frame.
6 | T_Cam0:
7 | cols: 4
8 | rows: 4
9 | data: [ 0.0149006, -0.9996865, 0.0201192, 0.0683705,
10 | -0.9998883, -0.014921 , -0.0008608, -0.0158797,
11 | 0.0011607, -0.0201041, -0.9997972, -0.0035799,
12 | 0.0, 0.0, 0.0, 1.0]
13 | rate_hz: 200
14 |
15 | # inertial sensor noise model parameters (static)
16 | gyroscope_noise_density: 1.6968e-04 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
17 | gyroscope_random_walk: 1.9393e-05 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
18 | accelerometer_noise_density: 2.0000e-3 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
19 | accelerometer_random_walk: 3.0000e-3 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
20 |
21 |
--------------------------------------------------------------------------------
/examples/euroc/dataset_utils.py:
--------------------------------------------------------------------------------
1 | import csv
2 | import os
3 | from typing import List
4 |
5 | import numpy as np
6 | import yaml
7 | from PIL import Image
8 | from scipy.spatial.transform import Rotation
9 |
10 | import cuvslam as vslam
11 |
12 |
13 | def load_frame(image_path: str) -> np.ndarray:
14 | """Load an image from a file path."""
15 | if not os.path.exists(image_path):
16 | raise FileNotFoundError(f"Image file not found: {image_path}")
17 |
18 | image = Image.open(image_path)
19 | frame = np.array(image)
20 |
21 | if image.mode == 'L':
22 | # mono8
23 | if len(frame.shape) != 2:
24 | raise ValueError("Expected mono8 image to have 2 dimensions [H W].")
25 | elif image.mode == 'RGB':
26 | # rgb8
27 | if len(frame.shape) != 3 or frame.shape[2] != 3:
28 | raise ValueError(
29 | "Expected rgb8 image to have 3 dimensions with 3 channels [H W C].")
30 | else:
31 | raise ValueError(f"Unsupported image mode: {image.mode}")
32 |
33 | return frame
34 |
35 |
36 | def transform_to_pose(transform_16: List[float]) -> vslam.Pose:
37 | """Convert a 4x4 transformation matrix to a vslam.Pose object."""
38 | transform = np.array(transform_16).reshape(4, 4)
39 | rotation_quat = Rotation.from_matrix(transform[:3, :3]).as_quat()
40 | return vslam.Pose(rotation=rotation_quat, translation=transform[:3, 3])
41 |
42 |
43 | def to_distortion_model(distortion: str) -> vslam.DistortionModel:
44 | """Convert string distortion model name to vslam.DistortionModel enum."""
45 | distortion_models = {
46 | 'pinhole': vslam.DistortionModel.Pinhole,
47 | 'fisheye': vslam.DistortionModel.Fisheye,
48 | 'brown': vslam.DistortionModel.Brown,
49 | 'polynomial': vslam.DistortionModel.Polynomial
50 | }
51 |
52 | distortion = distortion.lower()
53 | if distortion not in distortion_models:
54 | raise ValueError(f"Unknown distortion model: {distortion}")
55 |
56 | return distortion_models[distortion]
57 |
58 |
59 | def get_camera(yaml_path: str) -> vslam.Camera:
60 | """Get a Camera object from a sensor YAML file."""
61 | if not os.path.exists(yaml_path):
62 | raise FileNotFoundError(f"Sensor YAML not found: {yaml_path}")
63 | with open(yaml_path, 'r') as f:
64 | config = yaml.safe_load(f)
65 | cam = vslam.Camera()
66 | cam.distortion = vslam.Distortion(
67 | to_distortion_model(config['camera_model']),
68 | config['distortion_coefficients']
69 | )
70 | cam.focal = config['intrinsics'][0:2]
71 | cam.principal = config['intrinsics'][2:4]
72 | cam.size = config['resolution']
73 | cam.rig_from_camera = transform_to_pose(config['T_Cam0']['data'])
74 | return cam
75 |
76 |
77 | def get_imu_calibration(yaml_path: str) -> vslam.ImuCalibration:
78 | """Get an ImuCalibration object from a sensor YAML file."""
79 | if not os.path.exists(yaml_path):
80 | raise FileNotFoundError(f"Sensor YAML not found: {yaml_path}")
81 | with open(yaml_path, 'r') as f:
82 | config = yaml.safe_load(f)
83 | imu = vslam.ImuCalibration()
84 | imu.rig_from_imu = transform_to_pose(config['T_Cam0']['data'])
85 | imu.gyroscope_noise_density = config['gyroscope_noise_density']
86 | imu.gyroscope_random_walk = config['gyroscope_random_walk']
87 | imu.accelerometer_noise_density = config['accelerometer_noise_density']
88 | imu.accelerometer_random_walk = config['accelerometer_random_walk']
89 | imu.frequency = config['rate_hz']
90 | return imu
91 |
92 |
93 | def get_rig(euroc_path: str) -> vslam.Rig:
94 | """Get a Rig object from EuRoC dataset path."""
95 | if not os.path.exists(euroc_path):
96 | raise FileNotFoundError(f"EuRoC dataset path does not exist: {euroc_path}")
97 | rig = vslam.Rig()
98 | rig.cameras = [get_camera(os.path.join(euroc_path, cam, 'sensor_recalibrated.yaml'))
99 | for cam in ['cam0', 'cam1']]
100 | rig.imus = [get_imu_calibration(os.path.join(euroc_path, 'imu0', 'sensor_recalibrated.yaml'))]
101 | return rig
102 |
103 |
104 | def read_csv_data(csv_path: str, sensor_type: str) -> List[dict]:
105 | """Read timestamp and sensor data from CSV file."""
106 | if not os.path.exists(csv_path):
107 | raise FileNotFoundError(f"CSV file not found: {csv_path}")
108 |
109 | valid_sensors = {'camera', 'imu'}
110 | if sensor_type not in valid_sensors:
111 | raise ValueError(f"Unknown sensor type: {sensor_type}. Must be one of {valid_sensors}")
112 |
113 | data = []
114 | with open(csv_path, 'r') as f:
115 | next(f) # Skip header line
116 | reader = csv.reader(f)
117 | for row in reader:
118 | if not row: # Skip empty rows
119 | continue
120 | if sensor_type == 'camera':
121 | if len(row) < 2:
122 | raise ValueError(f"Invalid camera data format. Expected timestamp and filename, got: {row}")
123 | data.append({
124 | 'timestamp': int(row[0]),
125 | 'filename': row[1]
126 | })
127 | else: # imu
128 | if len(row) < 7:
129 | raise ValueError(f"Invalid IMU data format. Expected timestamp and 6 values, got: {row}")
130 | data.append({
131 | 'timestamp': int(row[0]),
132 | 'gyro': [float(x) for x in row[1:4]],
133 | 'accel': [float(x) for x in row[4:7]]
134 | })
135 |
136 | return data
137 |
138 |
139 | def prepare_frame_metadata_euroc(euroc_path: str, odometry_mode: vslam.TrackerOdometryMode) -> List[dict]:
140 | """Process EuRoC dataset camera files and generate synchronized frame metadata."""
141 | if not os.path.exists(euroc_path):
142 | raise ValueError(f"EuRoC dataset path does not exist: {euroc_path}")
143 |
144 | left_cam_csv = os.path.join(euroc_path, 'cam0', 'data.csv')
145 | right_cam_csv = os.path.join(euroc_path, 'cam1', 'data.csv')
146 |
147 | if not os.path.exists(left_cam_csv) or not os.path.exists(right_cam_csv):
148 | raise ValueError(f"Camera data CSV files not found in {left_cam_csv} or {right_cam_csv}")
149 |
150 | left_cam_data = read_csv_data(left_cam_csv, 'camera')
151 | right_cam_data = read_csv_data(right_cam_csv, 'camera')
152 |
153 | # Verify timestamps match between cameras
154 | if len(left_cam_data) != len(right_cam_data):
155 | raise ValueError("Number of frames differs between left and right cameras")
156 |
157 | for i, (left_cam, right_cam) in enumerate(zip(left_cam_data, right_cam_data)):
158 | if left_cam['timestamp'] != right_cam['timestamp']:
159 | raise ValueError(f"Timestamp mismatch at frame {i}")
160 |
161 | # Generate stereo frame metadata
162 | frames_metadata = [{
163 | 'type': 'stereo',
164 | 'timestamp': left_cam['timestamp'],
165 | 'images_paths': [
166 | os.path.join(euroc_path, 'cam0', 'data', left_cam['filename']),
167 | os.path.join(euroc_path, 'cam1', 'data', right_cam['filename']),
168 | ],
169 | } for left_cam, right_cam in zip(left_cam_data, right_cam_data)]
170 |
171 | # Add IMU data if in inertial mode
172 | if odometry_mode == vslam.TrackerOdometryMode.Inertial:
173 | imu_csv = os.path.join(euroc_path, 'imu0', 'data.csv')
174 | if not os.path.exists(imu_csv):
175 | raise ValueError(f"IMU data CSV file not found in {imu_csv}")
176 |
177 | imu_data = read_csv_data(imu_csv, 'imu')
178 | frames_metadata.extend({
179 | 'type': 'imu',
180 | 'timestamp': measurement['timestamp'],
181 | 'gyro': measurement['gyro'],
182 | 'accel': measurement['accel']
183 | } for measurement in imu_data)
184 |
185 | # Sort frames by timestamp
186 | frames_metadata.sort(key=lambda x: x['timestamp'])
187 |
188 | return frames_metadata
189 |
--------------------------------------------------------------------------------
/examples/euroc/track_euroc.py:
--------------------------------------------------------------------------------
1 | import os
2 |
3 | import numpy as np
4 | import rerun as rr
5 | import rerun.blueprint as rrb
6 |
7 | import cuvslam as vslam
8 | from dataset_utils import prepare_frame_metadata_euroc, get_rig, load_frame
9 |
10 | # Available tracking modes:
11 | # vslam.TrackerOdometryMode.Mono - Monocular visual odometry
12 | # vslam.TrackerOdometryMode.Multicamera - Stereo visual odometry
13 | # vslam.TrackerOdometryMode.Inertial - Visual-inertial odometry
14 |
15 | euroc_tracking_mode = vslam.TrackerOdometryMode.Inertial
16 |
17 | # Setup rerun visualizer
18 | rr.init("cuVSLAM Visualizer", spawn=True)
19 |
20 | # Setup coordinate basis for root, cuvslam uses right-hand system with X-right, Y-down, Z-forward
21 | rr.log("world", rr.ViewCoordinates.RIGHT_HAND_Y_DOWN, static=True)
22 |
23 | # Setup rerun views
24 | rr.send_blueprint(
25 | rrb.Blueprint(
26 | rrb.TimePanel(state="collapsed"),
27 | rrb.Horizontal(
28 | column_shares=[0.5, 0.5],
29 | contents=[
30 | rrb.Spatial2DView(origin='world/camera_0'),
31 | rrb.Spatial3DView(origin='world'),
32 |
33 | ]
34 | )
35 | )
36 | )
37 |
38 |
39 | # Generate pseudo-random color from integer identifier for visualization
40 | def color_from_id(identifier): return [(identifier * 17) % 256, (identifier * 31) % 256, (identifier * 47) % 256]
41 |
42 |
43 | # Prepare frames metadata
44 | euroc_dataset_path = os.path.join(os.path.dirname(__file__), "dataset/mav0")
45 | frames_metadata = prepare_frame_metadata_euroc(euroc_dataset_path, euroc_tracking_mode)
46 |
47 | # Get camera rig
48 | rig = get_rig(euroc_dataset_path)
49 |
50 | # Configure tracker
51 | cfg = vslam.TrackerConfig()
52 | cfg.odometry_mode = euroc_tracking_mode
53 | cfg.async_sba = False
54 | cfg.enable_observations_export = True
55 |
56 | # Initialize tracker
57 | tracker = vslam.Tracker(rig, cfg)
58 |
59 | # Track frames
60 | last_camera_timestamp = None
61 | imu_count_since_last_camera = 0
62 | frame_id = 0
63 | trajectory = []
64 | for frame_metadata in frames_metadata:
65 | timestamp = frame_metadata['timestamp']
66 | if frame_metadata['type'] == 'imu':
67 | imu_measurement = vslam.ImuMeasurement()
68 | imu_measurement.timestamp_ns = int(timestamp)
69 | imu_measurement.linear_accelerations = np.array(frame_metadata['accel'])
70 | imu_measurement.angular_velocities = np.array(frame_metadata['gyro'])
71 | tracker.register_imu_measurement(0, imu_measurement)
72 | imu_count_since_last_camera += 1
73 | continue
74 |
75 | images = [load_frame(image_path) for image_path in frame_metadata['images_paths']]
76 |
77 | # Check IMU measurements before tracking
78 | if cfg.odometry_mode == vslam.TrackerOdometryMode.Inertial and last_camera_timestamp is not None:
79 | if imu_count_since_last_camera == 0:
80 | print(f"Warning: No IMU measurements between timestamps {last_camera_timestamp} and {timestamp}")
81 |
82 | # Reset counters
83 | last_camera_timestamp = timestamp
84 | imu_count_since_last_camera = 0
85 |
86 | # Track frame
87 | pose_estimate = tracker.track(timestamp, images)
88 | trajectory.append(pose_estimate.pose.translation)
89 |
90 | # Visualize
91 |
92 | # Get current pose and observations for the main camera and gravity in rig frame
93 | current_pose = pose_estimate.pose
94 | current_observations_main_cam = tracker.get_last_observations(0)
95 | gravity = None
96 | if cfg.odometry_mode == vslam.TrackerOdometryMode.Inertial:
97 | # Gravity estimation requires collecting sufficient number of keyframes with motion diversity
98 | gravity = tracker.get_last_gravity()
99 |
100 | rr.set_time_sequence("frame", frame_id)
101 | rr.log("world/trajectory", rr.LineStrips3D(trajectory), static=True)
102 | rr.log(
103 | "world/camera_0",
104 | rr.Transform3D(translation=current_pose.translation, quaternion=current_pose.rotation),
105 | rr.Arrows3D(
106 | vectors=np.eye(3) * 0.2,
107 | colors=[[255, 0, 0], [0, 255, 0], [0, 0, 255]] # RGB for XYZ axes
108 | )
109 | )
110 |
111 | points = np.array([[obs.u, obs.v] for obs in current_observations_main_cam])
112 | colors = np.array([color_from_id(obs.id) for obs in current_observations_main_cam])
113 | rr.log(
114 | "world/camera_0/observations",
115 | rr.Points2D(positions=points, colors=colors, radii=5.0),
116 | rr.Image(images[0]).compress(jpeg_quality=80)
117 | )
118 | if gravity is not None:
119 | rr.log(
120 | "world/camera_0/gravity",
121 | rr.Arrows3D(vectors=gravity, colors=[[255, 0, 0]], radii=0.015)
122 | )
123 |
124 | frame_id += 1
125 |
--------------------------------------------------------------------------------
/examples/kitti/track_kitti.py:
--------------------------------------------------------------------------------
1 | from os.path import join
2 |
3 | import rerun as rr
4 | import rerun.blueprint as rrb
5 | from PIL import Image
6 | from numpy import loadtxt, asarray
7 |
8 | import cuvslam
9 |
10 | # Dataset sequence to track and visualize
11 | sequence_path = 'examples/kitti/dataset/sequences/06'
12 |
13 |
14 | # Generate pseudo-random colour from integer identifier for visualization
15 | def color_from_id(identifier): return [(identifier * 17) % 256, (identifier * 31) % 256, (identifier * 47) % 256]
16 |
17 |
18 | # Setup rerun visualizer
19 | rr.init('kitti', strict=True, spawn=True) # launch re-run instance
20 |
21 | # Setup rerun views
22 | rr.send_blueprint(rrb.Blueprint(rrb.TimePanel(state="collapsed"),
23 | rrb.Vertical(row_shares=[0.6, 0.4],
24 | contents=[rrb.Spatial3DView(), rrb.Spatial2DView(origin='car/cam0')])))
25 |
26 | # Setup coordinate basis for root, cuvslam uses right-hand system with X-right, Y-down, Z-forward
27 | rr.log("/", rr.ViewCoordinates.RIGHT_HAND_Y_DOWN, static=True)
28 |
29 | # Draw arrays in origin X-red, Y-green, Z-blue
30 | rr.log("xyz", rr.Arrows3D(vectors=[[50, 0, 0], [0, 50, 0], [0, 0, 50]], colors=[[255, 0, 0], [0, 255, 0], [0, 0, 255]],
31 | labels=['[x]', '[y]', '[z]']), static=True)
32 |
33 | # Load KITTI dataset (calibration, timestamps and image sizes)
34 | # Load projection matrices per camera [P0, P1, P2, P3]
35 | intrinsics = loadtxt(join(sequence_path, 'calib.txt'), usecols=range(1, 13)).reshape(4, 3, 4)
36 | size = Image.open(join(sequence_path, 'image_0', '000000.png')).size # assume all images have the same size
37 | timestamps = [int(10 ** 9 * float(sec_str)) for sec_str in open(join(sequence_path, 'times.txt')).readlines()]
38 |
39 | # Initialize the cuvslam tracker
40 | cameras = [cuvslam.Camera(), cuvslam.Camera()]
41 | for i in [0, 1]:
42 | cameras[i].size = size
43 | cameras[i].principal = [intrinsics[i][0][2], intrinsics[i][1][2]]
44 | cameras[i].focal = [intrinsics[i].diagonal()[0], intrinsics[i].diagonal()[1]]
45 | cameras[1].rig_from_camera.translation[0] = - intrinsics[1][0][3] / intrinsics[1][0][0] # stereo-camera baseline
46 | cfg = cuvslam.TrackerConfig(async_sba=False, enable_final_landmarks_export=True, horizontal_stereo_camera=True)
47 | tracker = cuvslam.Tracker(cuvslam.Rig(cameras), cfg)
48 |
49 | # Track each frames in the dataset sequence
50 | trajectory = []
51 | for frame in range(len(timestamps)):
52 | # Load grayscale pixels as array for left and right absolute image paths
53 | images = [asarray(Image.open(join(sequence_path, f'image_{cam}', f'{frame:0>6}.png'))) for cam in [0, 1]]
54 |
55 | # Do tracking
56 | result = tracker.track(timestamps[frame], images)
57 |
58 | # Get visualization data
59 | observations = tracker.get_last_observations(0) # get observation from left camera
60 | landmarks = tracker.get_last_landmarks()
61 | final_landmarks = tracker.get_final_landmarks()
62 |
63 | # Prepare visualization data
64 | observations_uv = [[o.u, o.v] for o in observations]
65 | observations_colors = [color_from_id(o.id) for o in observations]
66 | landmark_xyz = [l.coords for l in landmarks]
67 | landmarks_colors = [color_from_id(l.id) for l in landmarks]
68 | trajectory.append(result.pose.translation)
69 |
70 | # Send results to rerun for visualization
71 | rr.set_time_sequence('frame', frame)
72 | rr.log('trajectory', rr.LineStrips3D(trajectory))
73 | rr.log('final_landmarks', rr.Points3D(list(final_landmarks.values()), radii=0.1))
74 | rr.log('car', rr.Transform3D(translation=result.pose.translation, quaternion=result.pose.rotation))
75 | rr.log('car/body', rr.Boxes3D(centers=[0, 1.65 / 2, 0], sizes=[[1.6, 1.65, 2.71]]))
76 | rr.log('car/landmarks_center', rr.Points3D(landmark_xyz, radii=0.25, colors=landmarks_colors))
77 | rr.log('car/landmarks_lines', rr.Arrows3D(vectors=landmark_xyz, radii=0.05, colors=landmarks_colors))
78 | rr.log('car/cam0', rr.Pinhole(image_plane_distance=1.68, image_from_camera=intrinsics[0][:3, :3],
79 | width=size[0], height=size[1]))
80 | rr.log('car/cam0/image', rr.Image(images[0]).compress(jpeg_quality=80))
81 | rr.log('car/cam0/observations', rr.Points2D(observations_uv, radii=5, colors=observations_colors))
82 |
--------------------------------------------------------------------------------
/examples/multicamera_edex/dataset_utils.py:
--------------------------------------------------------------------------------
1 | import os
2 | import numpy as np
3 | import cuvslam as vslam
4 | from typing import List, Tuple
5 | from scipy.spatial.transform import Rotation
6 | import json
7 |
8 | def to_distortion_model(distortion: str) -> vslam.DistortionModel:
9 | """Convert string distortion model name to vslam.DistortionModel enum."""
10 | distortion_models = {
11 | 'pinhole': vslam.DistortionModel.Pinhole,
12 | 'fisheye': vslam.DistortionModel.Fisheye,
13 | 'brown': vslam.DistortionModel.Brown,
14 | 'polynomial': vslam.DistortionModel.Polynomial
15 | }
16 | if distortion not in distortion_models:
17 | raise ValueError(f"Unknown distortion model: {distortion}")
18 |
19 | return distortion_models[distortion]
20 |
21 | def opengl_to_opencv_transform(rotation: np.ndarray, translation: np.ndarray) -> Tuple[np.ndarray, np.ndarray]:
22 | """Convert from edex coordinate system to OpenCV coordinate system."""
23 | K = np.array([
24 | [1, 0, 0],
25 | [0, -1, 0],
26 | [0, 0, -1]])
27 | return (K @ rotation @ K.T), K @ translation
28 |
29 | def transform_to_pose(transform_16: List[float]) -> vslam.Pose:
30 | """Convert a 4x4 transformation matrix to a vslam.Pose object."""
31 | transform = np.array(transform_16).reshape([-1, 4])
32 | rotation_opencv, translation_opencv = opengl_to_opencv_transform(transform[:3, :3], transform[:3, 3])
33 | rotation_quat = Rotation.from_matrix(rotation_opencv).as_quat()
34 |
35 | return vslam.Pose(rotation = rotation_quat, translation = translation_opencv)
36 |
37 | def read_stereo_edex(file_path: str):
38 | if not os.path.exists(file_path):
39 | raise FileNotFoundError(f"EDEX file not found: {file_path}")
40 |
41 | with open(file_path, 'r') as file:
42 | data = json.load(file)
43 |
44 | cameras = []
45 | for idx, cam_data in enumerate(data[0]['cameras']):
46 | config = {
47 | 'camera_model': cam_data['intrinsics']['distortion_model'],
48 | 'distortion_coefficients': cam_data['intrinsics']['distortion_params'],
49 | 'intrinsics': cam_data['intrinsics']['focal'] + cam_data['intrinsics']['principal'],
50 | 'resolution': cam_data['intrinsics']['size'],
51 | 'extrinsics': cam_data['transform']
52 | }
53 |
54 | cam = vslam.Camera()
55 | cam.distortion = vslam.Distortion(
56 | to_distortion_model(config['camera_model']),
57 | config['distortion_coefficients']
58 | )
59 | cam.focal = config['intrinsics'][0:2]
60 | cam.principal = config['intrinsics'][2:4]
61 | cam.size = config['resolution']
62 | cam.rig_from_camera = transform_to_pose(config['extrinsics'])
63 |
64 | cameras.append(cam)
65 |
66 | return cameras
67 |
--------------------------------------------------------------------------------
/examples/multicamera_edex/track_multicamera.py:
--------------------------------------------------------------------------------
1 | import cuvslam as vslam
2 | import os
3 | import json
4 | import numpy as np
5 | import rerun as rr
6 | import rerun.blueprint as rrb
7 |
8 | from dataset_utils import read_stereo_edex
9 | from PIL import Image
10 |
11 | # generate pseudo-random colour from integer identifier for visualization
12 | def color_from_id(identifier): return [(identifier * 17) % 256, (identifier * 31) % 256, (identifier * 47) % 256]
13 |
14 | ### setup rerun visualizer
15 | rr.init('multicamera_hawk', strict=True, spawn=True) # launch re-run instance
16 | # setup rerun views
17 | rr.send_blueprint(rrb.Blueprint(rrb.TimePanel(state="collapsed"),
18 | rrb.Vertical(
19 | contents=[
20 | rrb.Horizontal(
21 | contents=[rrb.Spatial2DView(origin='car/cam0', name='front-stereo_left'),
22 | rrb.Spatial2DView(origin='car/cam1', name='front-stereo_right'),
23 | rrb.Spatial2DView(origin='car/cam2', name='back-stereo_left'),
24 | rrb.Spatial2DView(origin='car/cam3', name='back-stereo_right')]),
25 | rrb.Spatial3DView(name="3D", defaults=[rr.components.ImagePlaneDistance(0.5)]),
26 | rrb.Horizontal(
27 | contents=[rrb.Spatial2DView(origin='car/cam4', name='left-stereo_left'),
28 | rrb.Spatial2DView(origin='car/cam5', name='left-stereo_right'),
29 | rrb.Spatial2DView(origin='car/cam6', name='right-stereo_left'),
30 | rrb.Spatial2DView(origin='car/cam7', name='right-stereo_right')])
31 | ]
32 | ),
33 | ),
34 | make_active=True)
35 | # setup coordinate basis for root, cuvslam uses right-hand system with X-right, Y-down, Z-forward
36 | rr.log("/", rr.ViewCoordinates.RIGHT_HAND_Y_DOWN, static=True)
37 |
38 | # Load frame metadata
39 | with open(os.path.join('datasets/r2b_galileo_edex/frame_metadata.jsonl'), 'r') as f:
40 | frames_metadata = [json.loads(i) for i in f.readlines()]
41 |
42 | # Load camera configuration from EDEX file
43 | cameras = read_stereo_edex('datasets/r2b_galileo_edex/stereo.edex')
44 |
45 | # Set up VSLAM rig and tracker
46 | rig = vslam.Rig()
47 | rig.cameras = cameras
48 |
49 | cfg = vslam.TrackerConfig(enable_final_landmarks_export = True,
50 | odometry_mode = vslam.TrackerOdometryMode.Multicamera)
51 |
52 | tracker = vslam.Tracker(rig, cfg)
53 |
54 | trajectory = []
55 |
56 | # Process each frame
57 | for frame_id, frame in enumerate(frames_metadata):
58 | timestamp = max([i['timestamp'] for i in frame['cams']])
59 | images = [np.asarray(Image.open(os.path.join('datasets', 'r2b_galileo_edex', i['filename']))) for i in frame['cams']]
60 | # do multicamera visual tracking
61 | pose_estimate = tracker.track(timestamp, images)
62 | # get visualization data
63 | observations = [tracker.get_last_observations(i) for i in range(8)]
64 | landmarks = tracker.get_last_landmarks()
65 | final_landmarks = tracker.get_final_landmarks()
66 | # prepare visualization data
67 | observations_uv = [[[o.u, o.v] for o in obs_instance] for obs_instance in observations]
68 | observations_colors = [[color_from_id(o.id) for o in obs_instance] for obs_instance in observations]
69 | landmark_xyz = [l.coords for l in landmarks]
70 | landmarks_colors = [color_from_id(l.id) for l in landmarks]
71 | trajectory.append(pose_estimate.pose.translation)
72 | # send results to rerun for visualization
73 | rr.set_time_sequence('frame', frame_id)
74 | rr.log('trajectory', rr.LineStrips3D(trajectory))
75 | rr.log('final_landmarks', rr.Points3D(list(final_landmarks.values()), radii=0.01))
76 | rr.log('car', rr.Transform3D(translation=pose_estimate.pose.translation, quaternion=pose_estimate.pose.rotation))
77 | rr.log('car/body', rr.Boxes3D(centers=[0, 0.3 / 2, 0], sizes=[[0.35, 0.3, 0.66]]))
78 | rr.log('car/landmarks_center', rr.Points3D(landmark_xyz, radii=0.02, colors=landmarks_colors))
79 |
80 | for i in range(len(cameras)):
81 | rr.log('car/cam%s/image' % i, rr.Image(images[i]).compress(jpeg_quality=80))
82 | rr.log('car/cam%s/observations' % i, rr.Points2D(observations_uv[i], radii=5, colors=observations_colors[i]))
83 |
84 | # show only even cameras in 3D world
85 | if not i%2:
86 | rr.log('car/cam%s' % i, rr.Transform3D(translation=cameras[i].rig_from_camera.translation,
87 | rotation=rr.Quaternion(xyzw=cameras[i].rig_from_camera.rotation),
88 | from_parent=False))
89 | rr.log('car/cam%s' % i, rr.Pinhole(image_plane_distance=1.,
90 | image_from_camera=np.array([[cameras[i].focal[0], 0, cameras[i].principal[0]],
91 | [0, cameras[i].focal[1], cameras[i].principal[1]],
92 | [0, 0, 1]]),
93 | width=cameras[i].size[0], height=cameras[i].size[1]))
94 |
--------------------------------------------------------------------------------
/examples/oak-d/run_stereo.py:
--------------------------------------------------------------------------------
1 | import os
2 | import sys
3 | import numpy as np
4 | import depthai as dai
5 | import cuvslam as vslam
6 | from typing import Any, Dict
7 | from scipy.spatial.transform import Rotation
8 |
9 | # Add the realsense folder to the system path to import visualizer
10 | sys.path.insert(0, os.path.abspath(os.path.join(os.path.dirname(__file__), '../realsense')))
11 |
12 | from visualizer import RerunVisualizer
13 |
14 | def get_oak_camera(oak_params) -> vslam.Camera:
15 | """Get a Camera object from a sensor YAML file."""
16 | cam = vslam.Camera()
17 | cam.distortion = vslam.Distortion(
18 | to_distortion_model('polynomial'), oak_params['distortion']
19 | )
20 |
21 | cam.focal = oak_params['intrinsics'][0][0], oak_params['intrinsics'][1][1]
22 | cam.principal = oak_params['intrinsics'][0][2], oak_params['intrinsics'][1][2]
23 | cam.size = oak_params['resolution']
24 | cam.rig_from_camera = oak_transform_to_pose(oak_params['extrinsics'])
25 |
26 | # features within these outer frame will be ignored by cuvslam
27 | cam.border_top = 100
28 | cam.border_bottom = 0
29 | cam.border_left = 120
30 | cam.border_right = 120
31 | return cam
32 |
33 | def oak_transform_to_pose(oak_extrinsics) -> vslam.Pose:
34 | '''Convert 4d transformation matrix to cuvslam pose'''
35 | return vslam.Pose(rotation = Rotation.from_matrix(np.array(oak_extrinsics)[:3,:3]).as_quat(),
36 | translation = np.array(oak_extrinsics)[:3,3]/100) #convert to m
37 |
38 | def get_oak_rig(stereo_params) -> vslam.Rig:
39 | """Get a Rig object from EuRoC dataset path."""
40 | rig = vslam.Rig()
41 | rig.cameras = [get_oak_camera(stereo_params['left']), get_oak_camera(stereo_params['right'])]
42 | return rig
43 |
44 | def to_distortion_model(distortion: str) -> vslam.DistortionModel:
45 | """Convert string distortion model name to vslam.DistortionModel enum."""
46 | distortion_models = {
47 | 'pinhole': vslam.DistortionModel.Pinhole,
48 | 'fisheye': vslam.DistortionModel.Fisheye,
49 | 'brown': vslam.DistortionModel.Brown,
50 | 'polynomial': vslam.DistortionModel.Polynomial
51 | }
52 |
53 | distortion = distortion.lower()
54 | if distortion not in distortion_models:
55 | raise ValueError(f"Unknown distortion model: {distortion}")
56 |
57 | return distortion_models[distortion]
58 |
59 | def create_oak_pipeline() -> dai.Pipeline:
60 | """Create and configure the OAK-D pipeline."""
61 | pipeline = dai.Pipeline()
62 |
63 | # Create stereo pair (left and right cameras)
64 | left_camera = pipeline.createMonoCamera()
65 | right_camera = pipeline.createMonoCamera()
66 |
67 | # Set camera properties
68 | left_camera.setBoardSocket(dai.CameraBoardSocket.CAM_B)
69 | right_camera.setBoardSocket(dai.CameraBoardSocket.CAM_C)
70 |
71 | # Set resolution
72 | left_camera.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P)
73 | right_camera.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P)
74 |
75 | # Set FPS
76 | left_camera.setFps(30)
77 | right_camera.setFps(30)
78 |
79 | # Create output queues for both cameras
80 | left_out = pipeline.createXLinkOut()
81 | right_out = pipeline.createXLinkOut()
82 |
83 | left_out.setStreamName("left")
84 | right_out.setStreamName("right")
85 |
86 | # Link cameras to output
87 | left_camera.out.link(left_out.input)
88 | right_camera.out.link(right_out.input)
89 |
90 | resolution = left_camera.getResolutionSize()
91 |
92 | return pipeline, resolution
93 |
94 | def get_stereo_calibration(device: dai.Device, resolution) -> Dict[str, Dict[str, Any]]:
95 | """Get calibration data from the device."""
96 | stereo_camera = {'left': {}, 'right': {}}
97 |
98 | # Set image size
99 | stereo_camera['left']['resolution'] = resolution
100 | stereo_camera['right']['resolution'] = resolution
101 |
102 | # Read the calibration data
103 | calibData = device.readCalibration()
104 |
105 | # Get intrinsics for left and right cameras
106 | stereo_camera['left']['intrinsics'] = calibData.getCameraIntrinsics(dai.CameraBoardSocket.CAM_B)
107 | stereo_camera['right']['intrinsics'] = calibData.getCameraIntrinsics(dai.CameraBoardSocket.CAM_C)
108 |
109 | # Get distortion coefficients for left and right cameras
110 | stereo_camera['left']['distortion'] = calibData.getDistortionCoefficients(dai.CameraBoardSocket.CAM_B)[:8]
111 | stereo_camera['right']['distortion'] = calibData.getDistortionCoefficients(dai.CameraBoardSocket.CAM_C)[:8]
112 |
113 | # Get extrinsics (relative transformation between cameras)
114 | stereo_camera['left']['extrinsics'] = calibData.getCameraExtrinsics(dai.CameraBoardSocket.CAM_B, dai.CameraBoardSocket.CAM_A)
115 | stereo_camera['right']['extrinsics'] = calibData.getCameraExtrinsics(dai.CameraBoardSocket.CAM_C, dai.CameraBoardSocket.CAM_A)
116 |
117 | return stereo_camera
118 |
119 | prev_timestamp = None
120 | threshold_ns = 35 * 1e6 # 35ms in nanoseconds
121 |
122 | visualizer = RerunVisualizer()
123 | frame_id = 0
124 |
125 | trajectory = []
126 |
127 | # Create and configure the pipeline
128 | pipeline, resolution = create_oak_pipeline()
129 |
130 | # Connect to the device and start the pipeline
131 | with dai.Device(pipeline) as device:
132 | stereo_camera = get_stereo_calibration(device, resolution)
133 |
134 | # Output synchronization
135 | left_queue = device.getOutputQueue("left", 8, False)
136 | right_queue = device.getOutputQueue("right", 8, False)
137 |
138 | rig = get_oak_rig(stereo_camera)
139 | cfg = vslam.TrackerConfig(async_sba=False, enable_final_landmarks_export=True, horizontal_stereo_camera=False)
140 | tracker = vslam.Tracker(rig, cfg)
141 |
142 | # Capture and process stereo frames
143 | while True:
144 | left_frame = left_queue.get()
145 | right_frame = right_queue.get()
146 |
147 | left_ts = left_frame.getTimestamp()
148 | right_ts = right_frame.getTimestamp()
149 |
150 | timestamp_left = int((left_ts.seconds * 1e9) + (left_ts.microseconds * 1e3))
151 | timestamp_right = int((right_ts.seconds * 1e9) + (right_ts.microseconds * 1e3))
152 |
153 | # Check if frames are synchronized
154 | if abs(timestamp_left - timestamp_right) > 5e6:
155 | print(f"Warning: Stereo pair is not syncronized: timestamp difference: {abs(timestamp_left - timestamp_right)/1e6:.2f} ms")
156 | continue
157 |
158 | # Check timestamp difference with previous frame
159 | if prev_timestamp is not None:
160 | timestamp_diff = timestamp_left - prev_timestamp
161 | if timestamp_diff > threshold_ns:
162 | timestamp_diff_ms = timestamp_diff / 1e6 # Convert to milliseconds
163 | print(f"Warning: Camera stream message drop: timestamp gap ({timestamp_diff/1e6:.2f} ms) exceeds threshold {threshold_ns/1e6:.2f} ms")
164 |
165 | left_img = left_frame.getCvFrame()
166 | right_img = right_frame.getCvFrame()
167 |
168 | pose_estimate = tracker.track(timestamp_left, (left_img, right_img))
169 | trajectory.append(pose_estimate.pose.translation)
170 |
171 | frame_id += 1
172 |
173 | visualizer.visualize_frame(
174 | frame_id=frame_id,
175 | images=(left_img, right_img),
176 | pose=pose_estimate.pose,
177 | observations_main_cam=tracker.get_last_observations(0),
178 | trajectory=trajectory,
179 | timestamp=timestamp_left
180 | )
181 |
182 | prev_timestamp = timestamp_left
183 |
--------------------------------------------------------------------------------
/examples/realsense/camera_utils.py:
--------------------------------------------------------------------------------
1 | import numpy as np
2 | import cuvslam as vslam
3 | from scipy.spatial.transform import Rotation
4 | from typing import Dict, Any, Tuple
5 |
6 | def to_odometry_mode(mode: str) -> vslam.TrackerOdometryMode:
7 | """Convert string odometry mode to vslam.TrackerOdometryMode enum."""
8 | odometry_modes = {
9 | 'mono': vslam.TrackerOdometryMode.Mono,
10 | 'stereo': vslam.TrackerOdometryMode.Multicamera,
11 | 'inertial': vslam.TrackerOdometryMode.Inertial
12 | }
13 |
14 | mode = mode.lower()
15 | if mode not in odometry_modes:
16 | raise ValueError(f"Unknown odometry mode: {mode}")
17 |
18 | return odometry_modes[mode]
19 |
20 | def transform_to_pose(rs_transform = None) -> vslam.Pose:
21 | if rs_transform:
22 | """Convert transformations provided by realsense to a vslam.Pose object."""
23 | rotation_matrix, translation_vec = np.array(rs_transform.rotation).reshape([3, 3]), rs_transform.translation
24 | rotation_quat = Rotation.from_matrix(rotation_matrix).as_quat()
25 | else:
26 | rotation_matrix, translation_vec = np.eye(3), [0]*3
27 | rotation_quat = Rotation.from_matrix(rotation_matrix).as_quat()
28 | return vslam.Pose(rotation=rotation_quat, translation=translation_vec)
29 |
30 | # IMU is in opengl coordinate system
31 | def rig_from_imu_pose(rs_transform = None) -> vslam.Pose:
32 | rotation_matrix = np.array([[1, 0, 0], [0, -1, 0], [0, 0, -1]])
33 | rotation_quat = Rotation.from_matrix(rotation_matrix).as_quat()
34 | translation_vec = rotation_matrix @ rs_transform.translation
35 | return vslam.Pose(rotation=rotation_quat, translation=translation_vec)
36 |
37 |
38 | def get_rs_camera(rs_intrinsics, rs_extinsincs = None) -> vslam.Camera:
39 | """Get a Camera object from RealSense intrinsics."""
40 | cam = vslam.Camera()
41 | cam.distortion = vslam.Distortion(vslam.DistortionModel.Pinhole)
42 | cam.focal = rs_intrinsics.fx, rs_intrinsics.fy
43 | cam.principal = rs_intrinsics.ppx, rs_intrinsics.ppy
44 | cam.size = rs_intrinsics.width, rs_intrinsics.height
45 | cam.rig_from_camera = transform_to_pose(rs_extinsincs)
46 | return cam
47 |
48 | def get_rs_imu(imu_extrinsics, frequency: int = 200) -> vslam.ImuCalibration:
49 | """Get an IMU calibration object from RealSense extrinsics."""
50 | imu = vslam.ImuCalibration()
51 | imu.rig_from_imu = rig_from_imu_pose(imu_extrinsics)
52 | imu.gyroscope_noise_density = 6.0673370376614875e-03
53 | imu.gyroscope_random_walk = 3.6211951458325785e-05
54 | imu.accelerometer_noise_density = 3.3621979208052800e-02
55 | imu.accelerometer_random_walk = 9.8256589971851467e-04
56 | imu.frequency = frequency
57 | return imu
58 |
59 | def get_rs_stereo_rig(camera_params: Dict[str, Dict[str, Any]]) -> vslam.Rig:
60 | """Get a VIO Rig object with cameras from RealSense parameters."""
61 | rig = vslam.Rig()
62 | rig.cameras = [
63 | get_rs_camera(camera_params['left']['intrinsics']),
64 | get_rs_camera(camera_params['right']['intrinsics'], camera_params['right']['extrinsics'])
65 | ]
66 | return rig
67 |
68 | def get_rs_vio_rig(camera_params: Dict[str, Dict[str, Any]]) -> vslam.Rig:
69 | """Get a VIO Rig object with cameras and IMU from RealSense parameters."""
70 | rig = vslam.Rig()
71 | rig.cameras = [
72 | get_rs_camera(camera_params['left']['intrinsics']),
73 | get_rs_camera(camera_params['right']['intrinsics'], camera_params['right']['extrinsics'])
74 | ]
75 | rig.imus = [get_rs_imu(camera_params['imu']['cam_from_imu'])]
76 | return rig
--------------------------------------------------------------------------------
/examples/realsense/run_stereo.py:
--------------------------------------------------------------------------------
1 | import cuvslam as vslam
2 | import numpy as np
3 | import pyrealsense2 as rs
4 | from camera_utils import get_rs_stereo_rig, to_odometry_mode
5 | from visualizer import RerunVisualizer
6 |
7 | # Initialize RealSense configuration
8 | config = rs.config()
9 | pipeline = rs.pipeline()
10 |
11 | # Configure streams
12 | config.enable_stream(rs.stream.infrared, 1, 640, 360, rs.format.y8, 30)
13 | config.enable_stream(rs.stream.infrared, 2, 640, 360, rs.format.y8, 30)
14 |
15 | # Start pipeline to get intrinsics and extrinsics
16 | profile = pipeline.start(config)
17 | frames = pipeline.wait_for_frames()
18 | pipeline.stop()
19 |
20 | # Prepare camera parameters
21 | camera_params = {'left': {}, 'right': {}}
22 |
23 | # Get extrinsics and intrinsics
24 | camera_params['left']['intrinsics'] = frames[0].profile.as_video_stream_profile().intrinsics
25 | camera_params['right']['intrinsics'] = frames[1].profile.as_video_stream_profile().intrinsics
26 | camera_params['right']['extrinsics'] = frames[1].profile.get_extrinsics_to(frames[0].profile)
27 |
28 | # Configure tracker
29 | cfg = vslam.TrackerConfig(async_sba=False, enable_final_landmarks_export=True,
30 | odometry_mode = to_odometry_mode('stereo'), horizontal_stereo_camera=True)
31 |
32 | # Create rig using utility function
33 | rig = get_rs_stereo_rig(camera_params)
34 |
35 | # Initialize tracker and visualizer
36 | tracker = vslam.Tracker(rig, cfg)
37 |
38 | # Get device product line for setting a supporting resolution
39 | pipeline_wrapper = rs.pipeline_wrapper(pipeline)
40 | pipeline_profile = config.resolve(pipeline_wrapper)
41 | device = pipeline_profile.get_device()
42 |
43 | # Disable IR emitter if supported
44 | depth_sensor = device.query_sensors()[0]
45 | if depth_sensor.supports(rs.option.emitter_enabled):
46 | depth_sensor.set_option(rs.option.emitter_enabled, 0)
47 |
48 | visualizer = RerunVisualizer()
49 |
50 | # Start pipeline for tracking
51 | profile = pipeline.start(config)
52 |
53 | frame_id = 0
54 |
55 | prev_timestamp = None
56 | threshold_ns = 35 * 1e6 # 35ms in nanoseconds
57 |
58 | trajectory = []
59 |
60 | try:
61 |
62 | while True:
63 | # Wait for frames
64 | frames = pipeline.wait_for_frames()
65 |
66 | lframe = frames.get_infrared_frame(1)
67 | rframe = frames.get_infrared_frame(2)
68 | if not lframe or not rframe:
69 | continue
70 |
71 | timestamp = int(lframe.timestamp * 1e6) # Convert to nanoseconds
72 |
73 | # Check timestamp difference with previous frame
74 | if prev_timestamp is not None:
75 | timestamp_diff = timestamp - prev_timestamp
76 | if timestamp_diff > threshold_ns:
77 | print(f"Warning: Camera stream message drop: timestamp gap ({timestamp_diff/1e6:.2f} ms) exceeds threshold {threshold_ns/1e6:.2f} ms")
78 |
79 | # Store current timestamp for next iteration
80 | prev_timestamp = timestamp
81 |
82 | images = (np.asanyarray(lframe.get_data()), np.asanyarray(rframe.get_data()))
83 |
84 | # Track frame
85 | pose_estimate = tracker.track(timestamp, images)
86 |
87 | frame_id += 1
88 | trajectory.append(pose_estimate.pose.translation)
89 |
90 | # Visualize results
91 | visualizer.visualize_frame(
92 | frame_id=frame_id,
93 | images=images,
94 | pose=pose_estimate.pose,
95 | observations_main_cam=tracker.get_last_observations(0),
96 | trajectory=trajectory,
97 | timestamp=timestamp
98 | )
99 |
100 | finally:
101 | pipeline.stop()
102 |
--------------------------------------------------------------------------------
/examples/realsense/run_vio.py:
--------------------------------------------------------------------------------
1 | import pyrealsense2 as rs
2 | import numpy as np
3 | import cuvslam as vslam
4 | import queue
5 | import threading
6 | from camera_utils import get_rs_vio_rig, to_odometry_mode
7 | from copy import deepcopy
8 | from visualizer import RerunVisualizer
9 |
10 | class ThreadWithTimestamp:
11 | def __init__(self, low_rate_threshold_ns, high_rate_threshold_ns):
12 | self.prev_low_rate_timestamp = None
13 | self.prev_high_rate_timestamp = None
14 | self.low_rate_threshold_ns = low_rate_threshold_ns
15 | self.high_rate_threshold_ns = high_rate_threshold_ns
16 | self.last_low_rate_timestamp = None
17 |
18 | def imu_thread(tracker, q, thread_with_timestamp, motion_pipe):
19 | while True:
20 | imu_measurement = vslam.ImuMeasurement()
21 | imu_frames = motion_pipe.wait_for_frames()
22 | current_timestamp = int(imu_frames[0].timestamp*1e6)
23 | timestamp_diff = 0
24 |
25 | # Receive last available timestamp from low_rate_thread and print warning if necessary
26 | if thread_with_timestamp.last_low_rate_timestamp is not None and current_timestamp < thread_with_timestamp.last_low_rate_timestamp:
27 | print(f"Warning: The IMU stream timestamp is earlier than the previous timestamp from the Camera stream ({current_timestamp} < {thread_with_timestamp.last_low_rate_timestamp})")
28 | continue
29 |
30 | # Store own previous timestamp and compare with threshold
31 | if thread_with_timestamp.prev_high_rate_timestamp is not None:
32 | timestamp_diff = current_timestamp - thread_with_timestamp.prev_high_rate_timestamp
33 | if timestamp_diff > thread_with_timestamp.high_rate_threshold_ns:
34 | print(f"Warning: IMU stream message drop: timestamp gap ({timestamp_diff/1e6:.2f} ms) exceeds threshold {thread_with_timestamp.high_rate_threshold_ns/1e6:.2f} ms")
35 | elif timestamp_diff < 0:
36 | print(f"Warning: IMU messages are not sequential")
37 |
38 | if timestamp_diff < 0:
39 | continue
40 |
41 | thread_with_timestamp.prev_high_rate_timestamp = deepcopy(current_timestamp)
42 | imu_measurement.timestamp_ns = current_timestamp
43 | imu_measurement.linear_accelerations = np.frombuffer(imu_frames[0].get_data(), dtype=np.float32)[:3]
44 | imu_measurement.angular_velocities = np.frombuffer(imu_frames[1].get_data(), dtype=np.float32)[:3]
45 |
46 | if timestamp_diff > 0:
47 | tracker.register_imu_measurement(0, imu_measurement)
48 |
49 | def camera_thread(tracker, q, thread_with_timestamp, ir_pipe):
50 | while True:
51 | ir_frames = ir_pipe.wait_for_frames()
52 | ir_lframe = ir_frames.get_infrared_frame(1)
53 | ir_rframe = ir_frames.get_infrared_frame(2)
54 | current_timestamp = int(ir_lframe.timestamp*1e6)
55 |
56 | # Store own previous timestamp and compare with threshold
57 | if thread_with_timestamp.prev_low_rate_timestamp is not None:
58 | timestamp_diff = current_timestamp - thread_with_timestamp.prev_low_rate_timestamp
59 | if timestamp_diff > thread_with_timestamp.low_rate_threshold_ns:
60 | print(f"Warning: Camera stream message drop: timestamp gap ({timestamp_diff/1e6:.2f} ms) exceeds threshold {thread_with_timestamp.low_rate_threshold_ns/1e6:.2f} ms")
61 |
62 | thread_with_timestamp.prev_low_rate_timestamp = deepcopy(current_timestamp)
63 | images = (np.asanyarray(ir_lframe.get_data()), np.asanyarray(ir_rframe.get_data()))
64 |
65 | pose_estimate = tracker.track(current_timestamp, images)
66 | q.put([current_timestamp, pose_estimate, images]) # Put the output in the queue for other processes
67 | thread_with_timestamp.last_low_rate_timestamp = current_timestamp
68 |
69 | # Initialize RealSense configuration
70 | config = rs.config()
71 | pipeline = rs.pipeline()
72 |
73 | # Configure streams for initial setup
74 | config.enable_stream(rs.stream.infrared, 1, 640, 360, rs.format.y8, 30)
75 | config.enable_stream(rs.stream.infrared, 2, 640, 360, rs.format.y8, 30)
76 | config.enable_stream(rs.stream.accel, rs.format.motion_xyz32f, 200)
77 | config.enable_stream(rs.stream.gyro, rs.format.motion_xyz32f, 200)
78 |
79 | # Start pipeline to get intrinsics and extrinsics
80 | profile = pipeline.start(config)
81 | frames = pipeline.wait_for_frames()
82 | pipeline.stop()
83 |
84 | # Prepare camera parameters
85 | camera_params = {'left': {}, 'right': {}, 'imu': {}}
86 |
87 | # Get extrinsics and intrinsics
88 | camera_params['right']['extrinsics'] = frames[1].profile.get_extrinsics_to(frames[0].profile)
89 | camera_params['imu']['cam_from_imu'] = frames[2].profile.get_extrinsics_to(frames[0].profile)
90 | camera_params['left']['intrinsics'] = frames[0].profile.as_video_stream_profile().intrinsics
91 | camera_params['right']['intrinsics'] = frames[1].profile.as_video_stream_profile().intrinsics
92 |
93 | # Configure tracker
94 | cfg = vslam.TrackerConfig(async_sba=False, enable_final_landmarks_export=True, debug_imu_mode = False,
95 | odometry_mode = to_odometry_mode('inertial'), horizontal_stereo_camera=True)
96 |
97 | # Create rig using utility function
98 | rig = get_rs_vio_rig(camera_params)
99 |
100 | # Initialize tracker
101 | tracker = vslam.Tracker(rig, cfg)
102 |
103 | # Set up IR pipeline
104 | ir_pipe = rs.pipeline()
105 | ir_config = rs.config()
106 | ir_config.enable_stream(rs.stream.infrared, 1, 640, 360, rs.format.y8, 30)
107 | ir_config.enable_stream(rs.stream.infrared, 2, 640, 360, rs.format.y8, 30)
108 |
109 | # Get device info
110 | ir_wrapper = rs.pipeline_wrapper(ir_pipe)
111 | ir_profile = config.resolve(ir_wrapper)
112 | device = ir_profile.get_device()
113 | device_product_line = str(device.get_info(rs.camera_info.product_line))
114 |
115 | # Disable IR emitter if supported
116 | depth_sensor = device.query_sensors()[0]
117 | if depth_sensor.supports(rs.option.emitter_enabled):
118 | depth_sensor.set_option(rs.option.emitter_enabled, 0)
119 |
120 | # Set up motion pipeline
121 | motion_pipe = rs.pipeline()
122 | motion_config = rs.config()
123 | motion_config.enable_stream(rs.stream.accel, rs.format.motion_xyz32f, 200)
124 | motion_config.enable_stream(rs.stream.gyro, rs.format.motion_xyz32f, 200)
125 |
126 | # Start pipelines
127 | motion_profile = motion_pipe.start(motion_config)
128 | ir_profile = ir_pipe.start(ir_config)
129 |
130 | # Set up threading and visualization
131 | q = queue.Queue()
132 | camera_threshold_ns = 35*1e6 # Define threshold in nanoseconds for low rate thread
133 | imu_threshold_ns = 5.5*1e6
134 |
135 | visualizer = RerunVisualizer()
136 | thread_with_timestamp = ThreadWithTimestamp(camera_threshold_ns, imu_threshold_ns)
137 |
138 | # Start threads
139 | t1 = threading.Thread(target=imu_thread, args=(tracker, q, thread_with_timestamp, motion_pipe))
140 | t2 = threading.Thread(target=camera_thread, args=(tracker, q, thread_with_timestamp, ir_pipe))
141 |
142 | t1.start()
143 | t2.start()
144 |
145 | frame_id = 0
146 | prev_timestamp = None
147 |
148 | trajectory = []
149 | try:
150 | while True:
151 |
152 | # Get the output from the queue
153 | timestamp, pose_estimate, images = q.get()
154 |
155 | frame_id += 1
156 | trajectory.append(pose_estimate.pose.translation)
157 |
158 | gravity = None
159 | if cfg.odometry_mode == vslam.TrackerOdometryMode.Inertial:
160 | # Gravity estimation requires collecting sufficient number of keyframes with motion diversity
161 | # Get gravity in rig frame
162 | gravity = tracker.get_last_gravity()
163 |
164 | # Visualize results
165 | visualizer.visualize_frame(
166 | frame_id=frame_id,
167 | images=images,
168 | pose=pose_estimate.pose,
169 | observations_main_cam=tracker.get_last_observations(0),
170 | trajectory=trajectory,
171 | timestamp=timestamp,
172 | gravity=gravity
173 | )
174 |
175 | finally:
176 | motion_pipe.stop()
177 | ir_pipe.stop()
--------------------------------------------------------------------------------
/examples/realsense/visualizer.py:
--------------------------------------------------------------------------------
1 | from typing import List
2 | import numpy as np
3 | import rerun as rr
4 | import rerun.blueprint as rrb
5 | import cuvslam as vslam
6 |
7 |
8 | class RerunVisualizer:
9 | def __init__(self):
10 | """Initialize rerun visualizer."""
11 | rr.init("cuVSLAM Visualizer", spawn=True)
12 | rr.log("world", rr.ViewCoordinates.RIGHT_HAND_Y_DOWN, static=True)
13 | rr.send_blueprint(
14 | rrb.Blueprint(
15 | rrb.TimePanel(state="collapsed"),
16 | rrb.Horizontal(
17 | column_shares=[0.5, 0.5],
18 | contents=[
19 | rrb.Spatial2DView(origin='world/camera_0'),
20 | rrb.Spatial3DView(origin='world'),
21 |
22 | ]
23 | )
24 | ),
25 | make_active=True
26 | )
27 | self.track_colors = {}
28 |
29 | def _log_rig_pose(self, rotation_quat: np.ndarray,
30 | translation: np.ndarray) -> None:
31 | """Log rig pose to Rerun."""
32 | scale = 0.1
33 | rr.log(
34 | "world/camera_0",
35 | rr.Transform3D(translation=translation, quaternion=rotation_quat),
36 | rr.Arrows3D(
37 | vectors=np.eye(3) * scale,
38 | colors=[[255,0,0], [0,255,0], [0,0,255]] # RGB for XYZ axes
39 | )
40 | )
41 |
42 | def _log_observations(self, observations_main_cam: List[vslam.Observation],
43 | image: np.ndarray) -> None:
44 | """Log 2D observations for a specific camera with consistent colors per track."""
45 | if not observations_main_cam:
46 | return
47 |
48 | # Assign random color to new tracks
49 | for obs in observations_main_cam:
50 | if obs.id not in self.track_colors:
51 | self.track_colors[obs.id] = np.random.randint(0, 256, size=3)
52 |
53 | points = np.array([[obs.u, obs.v] for obs in observations_main_cam])
54 | colors = np.array([self.track_colors[obs.id] for obs in observations_main_cam])
55 |
56 | rr.log(
57 | "world/camera_0/observations",
58 | rr.Points2D(positions=points, colors=colors, radii=5.0),
59 | rr.Image(image).compress()
60 | )
61 |
62 | def _log_gravity(self, gravity: np.ndarray) -> None:
63 | """Log gravity vector to Rerun."""
64 | scale = 0.02
65 | rr.log(
66 | "world/camera_0/gravity",
67 | rr.Arrows3D(vectors=gravity, colors=[[255, 0, 0]], radii=scale)
68 | )
69 |
70 | def visualize_frame(self, frame_id: int, images: List[np.ndarray],
71 | pose: vslam.Pose, observations_main_cam: List[vslam.Observation],
72 | trajectory: List[np.ndarray], timestamp: int, gravity: np.ndarray = None) -> None:
73 | """Visualize current frame state using Rerun."""
74 | rr.set_time_sequence("frame", frame_id)
75 | rr.log("world/trajectory", rr.LineStrips3D(trajectory), static=True)
76 | for camera_idx, image in enumerate(images):
77 | # Visualize main camera
78 | if camera_idx == 0:
79 | self._log_rig_pose(pose.rotation, pose.translation)
80 | self._log_observations(observations_main_cam, image)
81 | if gravity is not None:
82 | self._log_gravity(gravity)
83 | rr.log("world/timestamp", rr.TextLog(str(timestamp)))
84 |
--------------------------------------------------------------------------------
/examples/requirements.txt:
--------------------------------------------------------------------------------
1 | numpy==2.2.4
2 | pillow==11.1.0
3 | pyyaml==6.0.2
4 | rerun-sdk==0.22.1
5 | scipy==1.14.1
6 |
--------------------------------------------------------------------------------
/pycuvslam.gif:
--------------------------------------------------------------------------------
1 | version https://git-lfs.github.com/spec/v1
2 | oid sha256:47492d936e16835dfb43fed86ccac18e8ef63748a9370932cfbff7af8df6d8e0
3 | size 7765436
4 |
--------------------------------------------------------------------------------
/run_docker.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | XSOCK=/tmp/.X11-unix
3 | XAUTH=/tmp/.docker.xauth
4 | DATASETS=$(realpath -s ~/datasets)
5 | xauth nlist "$DISPLAY" | sed -e 's/^..../ffff/' | xauth -f $XAUTH nmerge -
6 | chmod 777 $XAUTH
7 | docker run -it \
8 | --runtime=nvidia \
9 | --rm \
10 | --gpus all \
11 | --privileged \
12 | --network host \
13 | -e NVIDIA_DRIVER_CAPABILITIES=all \
14 | -e DISPLAY="$DISPLAY" \
15 | -e XAUTHORITY=$XAUTH \
16 | -v $XSOCK:$XSOCK \
17 | -v $XAUTH:$XAUTH \
18 | -v .:/pycuvslam \
19 | -v "$DATASETS":"$DATASETS" \
20 | pycuvslam
21 |
--------------------------------------------------------------------------------