Skip to content

Commit ec57b53

Browse files
Isaac ROS 4.0 (#204)
1 parent 19be8c7 commit ec57b53

17 files changed

+1257
-86
lines changed

README.md

Lines changed: 3 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
NVIDIA-accelerated, simultaneous localization and mapping (SLAM) using stereo
44
visual inertial odometry (SVIO).
55

6-
<div align="center"><a class="reference internal image-reference" href="https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/main/resources/isaac_ros_docs/repositories_and_packages/isaac_ros_visual_slam/cuvslam_ros_3.gif/"><img alt="image" src="https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/main/resources/isaac_ros_docs/repositories_and_packages/isaac_ros_visual_slam/cuvslam_ros_3.gif/" width="800px"/></a></div>
6+
<div align="center"><a class="reference internal image-reference" href="https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/release-4.0/resources/isaac_ros_docs/repositories_and_packages/isaac_ros_visual_slam/cuvslam_ros_3.gif/"><img alt="image" src="https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/release-4.0/resources/isaac_ros_docs/repositories_and_packages/isaac_ros_visual_slam/cuvslam_ros_3.gif/" width="800px"/></a></div>
77

88
---
99

@@ -61,7 +61,7 @@ closure. VSLAM uses a statistical approach to loop closure that is more
6161
compute efficient to provide a real time solution, improving convergence
6262
in loop closure.
6363

64-
<div align="center"><a class="reference internal image-reference" href="https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/main/resources/isaac_ros_docs/repositories_and_packages/isaac_ros_visual_slam/vslam_odometry_nav2_diagram.png/"><img alt="image" src="https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/main/resources/isaac_ros_docs/repositories_and_packages/isaac_ros_visual_slam/vslam_odometry_nav2_diagram.png/" width="880px"/></a></div>
64+
<div align="center"><a class="reference internal image-reference" href="https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/release-4.0/resources/isaac_ros_docs/repositories_and_packages/isaac_ros_visual_slam/vslam_odometry_nav2_diagram.png/"><img alt="image" src="https://media.githubusercontent.com/media/NVIDIA-ISAAC-ROS/.github/release-4.0/resources/isaac_ros_docs/repositories_and_packages/isaac_ros_visual_slam/vslam_odometry_nav2_diagram.png/" width="880px"/></a></div>
6565

6666
There are multiple methods for estimating odometry as an input to
6767
navigation. None of these methods are perfect; each has limitations
@@ -99,15 +99,6 @@ In addition to results from standard benchmarks, we test loop closure
9999
for VSLAM on sequences of over 1000 meters, with coverage for indoor and
100100
outdoor scenes.
101101

102-
## Performance
103-
104-
| Sample Graph<br/><br/> | Input Size<br/><br/> | Nova Carter<br/><br/> |
105-
|----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|---------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------|
106-
| [Multicam Visual SLAM Live Graph](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/benchmarks/isaac_ros_perceptor_nova_benchmark/scripts/isaac_ros_visual_slam_graph.py)<br/><br/><br/>4 Hawk Cameras<br/><br/> | 1200p<br/><br/><br/><br/> | [30.1 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_4_hawk_vslam_graph-carter-v2.4-jp6.json)<br/><br/><br/><br/> |
107-
108-
> [!Note]
109-
> This benchmark can only be run on a [Nova Orin](https://developer.nvidia.com/isaac/nova-orin) compatible system.
110-
111102
---
112103

113104
## Documentation
@@ -129,4 +120,4 @@ this repository.
129120

130121
## Latest
131122

132-
Update 2024-12-10: Add support for multi-cam SLAM mode on stereo RGB cameras
123+
Update 2025-10-24: Support for ROS 2 Jazzy with cuVSLAM 14

SECURITY.md

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
## Security
2+
3+
NVIDIA is dedicated to the security and trust of our software products and services, including all source code repositories managed through our organization.
4+
5+
If you need to report a security issue, please use the appropriate contact points outlined below. **Please do not report security vulnerabilities through GitHub.**
6+
7+
## Reporting Potential Security Vulnerability in an NVIDIA Product
8+
9+
To report a potential security vulnerability in any NVIDIA product:
10+
- Web: [Security Vulnerability Submission Form](https://www.nvidia.com/object/submit-security-vulnerability.html)
11+
12+
- We encourage you to use the following PGP key for secure email communication: [NVIDIA public PGP Key for communication](https://www.nvidia.com/en-us/security/pgp-key)
13+
- Please include the following information:
14+
- Product/Driver name and version/branch that contains the vulnerability
15+
- Type of vulnerability (code execution, denial of service, buffer overflow, etc.)
16+
- Instructions to reproduce the vulnerability
17+
- Proof-of-concept or exploit code
18+
- Potential impact of the vulnerability, including how an attacker could exploit the vulnerability
19+
20+
While NVIDIA currently does not have a bug bounty program, we do offer acknowledgement when an externally reported security issue is addressed under our coordinated vulnerability disclosure policy. Please visit our [Product Security Incident Response Team (PSIRT)](https://www.nvidia.com/en-us/security/psirt-policies/) policies page for more information.
21+
22+
## NVIDIA Product Security
23+
24+
For all security-related concerns, please visit NVIDIA's Product Security portal at https://www.nvidia.com/en-us/security

isaac_ros_visual_slam/CMakeLists.txt

Lines changed: 13 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,10 +25,21 @@ endif()
2525
execute_process(COMMAND uname -m COMMAND tr -d '\n' OUTPUT_VARIABLE ARCHITECTURE)
2626
message( STATUS "Architecture: ${ARCHITECTURE}" )
2727

28-
find_package(Boost COMPONENTS thread REQUIRED)
28+
find_package(Boost COMPONENTS thread chrono REQUIRED)
2929
find_package(ament_cmake_auto REQUIRED)
3030
ament_auto_find_build_dependencies()
3131

32+
# Ensure CUDA imported targets (e.g., CUDA::nvtx3) are available
33+
find_package(CUDAToolkit REQUIRED)
34+
35+
# NVTX
36+
option(USE_NVTX "Enable NVTX markers for improved profiling (if available)" ON)
37+
if(USE_NVTX)
38+
add_definitions(-DUSE_NVTX)
39+
link_directories("${CUDA_TOOLKIT_ROOT_DIR}/lib64")
40+
link_libraries("CUDA::nvtx3")
41+
endif()
42+
3243
# Dependencies
3344
find_package(Threads REQUIRED)
3445
find_package(Eigen3 REQUIRED)
@@ -62,7 +73,7 @@ ament_auto_add_library(
6273
src/impl/visual_slam_impl.cpp
6374
src/impl/viz_helper.cpp
6475
)
65-
target_link_libraries(visual_slam_node cuvslam Boost::thread)
76+
target_link_libraries(visual_slam_node cuvslam Boost::thread Boost::chrono)
6677
rclcpp_components_register_nodes(visual_slam_node "nvidia::isaac_ros::visual_slam::VisualSlamNode")
6778
set(node_plugins "${node_plugins}nvidia::isaac_ros::visual_slam::VisualSlamNode;$<TARGET_FILE:visual_slam_node>\n")
6879

Lines changed: 283 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,283 @@
1+
{
2+
"configById": {
3+
"Image!3qezyf6": {
4+
"cameraState": {
5+
"distance": 20,
6+
"perspective": true,
7+
"phi": 60,
8+
"target": [
9+
0,
10+
0,
11+
0
12+
],
13+
"targetOffset": [
14+
0,
15+
0,
16+
0
17+
],
18+
"targetOrientation": [
19+
0,
20+
0,
21+
0,
22+
1
23+
],
24+
"thetaOffset": 45,
25+
"fovy": 45,
26+
"near": 0.5,
27+
"far": 5000
28+
},
29+
"followMode": "follow-pose",
30+
"scene": {},
31+
"transforms": {},
32+
"topics": {},
33+
"layers": {},
34+
"publish": {
35+
"type": "point",
36+
"poseTopic": "/move_base_simple/goal",
37+
"pointTopic": "/clicked_point",
38+
"poseEstimateTopic": "/initialpose",
39+
"poseEstimateXDeviation": 0.5,
40+
"poseEstimateYDeviation": 0.5,
41+
"poseEstimateThetaDeviation": 0.26179939
42+
},
43+
"imageMode": {
44+
"imageTopic": "/dnn_image_encoder/crop/image"
45+
}
46+
},
47+
"Image!3rc5faz": {
48+
"cameraState": {
49+
"distance": 20,
50+
"perspective": true,
51+
"phi": 60,
52+
"target": [
53+
0,
54+
0,
55+
0
56+
],
57+
"targetOffset": [
58+
0,
59+
0,
60+
0
61+
],
62+
"targetOrientation": [
63+
0,
64+
0,
65+
0,
66+
1
67+
],
68+
"thetaOffset": 45,
69+
"fovy": 45,
70+
"near": 0.5,
71+
"far": 5000
72+
},
73+
"followMode": "follow-pose",
74+
"scene": {},
75+
"transforms": {},
76+
"topics": {},
77+
"layers": {},
78+
"publish": {
79+
"type": "point",
80+
"poseTopic": "/move_base_simple/goal",
81+
"pointTopic": "/clicked_point",
82+
"poseEstimateTopic": "/initialpose",
83+
"poseEstimateXDeviation": 0.5,
84+
"poseEstimateYDeviation": 0.5,
85+
"poseEstimateThetaDeviation": 0.26179939
86+
},
87+
"imageMode": {
88+
"imageTopic": "/segformer/colored_segmentation_mask"
89+
}
90+
},
91+
"3D!18i6zy7": {
92+
"layers": {
93+
"845139cb-26bc-40b3-8161-8ab60af4baf5": {
94+
"visible": true,
95+
"frameLocked": true,
96+
"label": "Grid",
97+
"instanceId": "845139cb-26bc-40b3-8161-8ab60af4baf5",
98+
"layerId": "foxglove.Grid",
99+
"size": 10,
100+
"divisions": 10,
101+
"lineWidth": 1,
102+
"color": "#248eff",
103+
"position": [
104+
0,
105+
0,
106+
0
107+
],
108+
"rotation": [
109+
0,
110+
0,
111+
0
112+
],
113+
"order": 1
114+
}
115+
},
116+
"cameraState": {
117+
"distance": 6.470670899401072,
118+
"perspective": true,
119+
"phi": 63.398075062165034,
120+
"target": [
121+
0,
122+
0,
123+
0
124+
],
125+
"targetOffset": [
126+
1.9527635164661725,
127+
0.7053742715758473,
128+
-8.596645199798259e-16
129+
],
130+
"targetOrientation": [
131+
0,
132+
0,
133+
0,
134+
1
135+
],
136+
"thetaOffset": 62.42882674013647,
137+
"fovy": 45,
138+
"near": 0.5,
139+
"far": 5000
140+
},
141+
"followMode": "follow-pose",
142+
"followTf": "odom",
143+
"scene": {
144+
"meshUpAxis": "z_up",
145+
"transforms": {
146+
"labelSize": 0.1
147+
}
148+
},
149+
"transforms": {
150+
"frame:base_link": {
151+
"visible": true
152+
},
153+
"frame:camera1_infra1_frame": {
154+
"visible": true
155+
},
156+
"frame:camera1_infra2_frame": {
157+
"visible": true
158+
},
159+
"frame:camera2_infra1_frame": {
160+
"visible": true
161+
},
162+
"frame:camera2_infra2_frame": {
163+
"visible": true
164+
}
165+
},
166+
"topics": {
167+
"/robot_description": {
168+
"visible": true
169+
},
170+
"/pointcloud": {
171+
"visible": false,
172+
"colorField": "z",
173+
"colorMode": "colormap",
174+
"colorMap": "turbo"
175+
},
176+
"/visual_slam/tracking/vo_path": {
177+
"visible": true,
178+
"lineWidth": 0.05,
179+
"gradient": [
180+
"#17c426ff",
181+
"#17c426ff"
182+
]
183+
},
184+
"/visual_slam/vis/observations_cloud": {
185+
"visible": true,
186+
"colorField": "rgb",
187+
"colorMode": "rgb",
188+
"colorMap": "turbo",
189+
"pointSize": 6
190+
},
191+
"/visual_slam/vis/landmarks_cloud": {
192+
"visible": false,
193+
"colorField": "rgb",
194+
"colorMode": "rgb",
195+
"colorMap": "turbo"
196+
},
197+
"/camera1/infra1/image_rect_raw": {
198+
"visible": true,
199+
"frameLocked": true,
200+
"cameraInfoTopic": "/camera1/infra1/camera_info",
201+
"distance": 1,
202+
"planarProjectionFactor": 0,
203+
"color": "#ffffff"
204+
},
205+
"/camera2/infra1/image_rect_raw": {
206+
"visible": true,
207+
"frameLocked": true,
208+
"cameraInfoTopic": "/camera2/infra1/camera_info",
209+
"distance": 1,
210+
"planarProjectionFactor": 0,
211+
"color": "#ffffff"
212+
},
213+
"/camera/infra1/camera_info": {
214+
"visible": false
215+
},
216+
"/camera/infra1/image_rect_raw": {
217+
"visible": false,
218+
"frameLocked": true,
219+
"cameraInfoTopic": "/camera/infra1/camera_info",
220+
"distance": 1,
221+
"planarProjectionFactor": 0,
222+
"color": "#ffffff"
223+
},
224+
"/camera/infra2/camera_info": {
225+
"visible": false
226+
},
227+
"/dnn_image_encoder/crop/image": {
228+
"visible": false,
229+
"frameLocked": true,
230+
"cameraInfoTopic": "/dnn_image_encoder/crop/camera_info",
231+
"distance": 1,
232+
"planarProjectionFactor": 0,
233+
"color": "#ffffff"
234+
},
235+
"/dnn_image_encoder/resize/image": {
236+
"visible": false,
237+
"frameLocked": true,
238+
"cameraInfoTopic": "/dnn_image_encoder/resize/camera_info",
239+
"distance": 1,
240+
"planarProjectionFactor": 0,
241+
"color": "#ffffff"
242+
},
243+
"/visual_slam/seg_mask_1": {
244+
"visible": false
245+
},
246+
"/segformer/raw_segmentation_mask": {
247+
"visible": false
248+
},
249+
"/segformer/colored_segmentation_mask": {
250+
"visible": false
251+
},
252+
"/dnn_image_encoder/resize/camera_info": {
253+
"visible": false
254+
}
255+
},
256+
"publish": {
257+
"type": "pose",
258+
"poseTopic": "/goal_pose",
259+
"pointTopic": "/clicked_point",
260+
"poseEstimateTopic": "/initialpose",
261+
"poseEstimateXDeviation": 0.5,
262+
"poseEstimateYDeviation": 0.5,
263+
"poseEstimateThetaDeviation": 0.26179939
264+
},
265+
"imageMode": {}
266+
}
267+
},
268+
"globalVariables": {},
269+
"userNodes": {},
270+
"playbackConfig": {
271+
"speed": 1
272+
},
273+
"layout": {
274+
"direction": "row",
275+
"first": {
276+
"first": "Image!3qezyf6",
277+
"second": "Image!3rc5faz",
278+
"direction": "column"
279+
},
280+
"second": "3D!18i6zy7",
281+
"splitPercentage": 37.166666666666664
282+
}
283+
}

0 commit comments

Comments
 (0)