Basalt VIO RTab
The example sets up a pipeline integrating stereo cameras, IMU, and visual odometry with RTAB-Map SLAM to generate and visualize 3D occupancy grids, point clouds, and rectified images in real-time using a RerunNode for visualization, with precise stereo depth and IMU configurations at 60 FPS.Setup
This example requires the DepthAI v3 API, see installation instructions.Pipeline
Source code
Python
C++
Python
PythonGitHub
1import time
2import depthai as dai
3from rerun_node import RerunNode
4
5# Create pipeline
6
7with dai.Pipeline() as p:
8 fps = 60
9 width = 640
10 height = 400
11 # Define sources and outputs
12 left = p.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_B, sensorFps=fps)
13 right = p.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_C, sensorFps=fps)
14 imu = p.create(dai.node.IMU)
15 odom = p.create(dai.node.BasaltVIO)
16 slam = p.create(dai.node.RTABMapSLAM)
17 stereo = p.create(dai.node.StereoDepth)
18 params = {"RGBD/CreateOccupancyGrid": "true",
19 "Grid/3D": "true",
20 "Rtabmap/SaveWMState": "true"}
21 slam.setParams(params)
22
23 rerunViewer = RerunNode()
24 imu.enableIMUSensor([dai.IMUSensor.ACCELEROMETER_RAW, dai.IMUSensor.GYROSCOPE_RAW], 200)
25 imu.setBatchReportThreshold(1)
26 imu.setMaxBatchReports(10)
27
28 stereo.setExtendedDisparity(False)
29 stereo.setLeftRightCheck(True)
30 stereo.setSubpixel(True)
31 stereo.setRectifyEdgeFillColor(0)
32 stereo.enableDistortionCorrection(True)
33 stereo.initialConfig.setLeftRightCheckThreshold(10)
34 stereo.setDepthAlign(dai.CameraBoardSocket.CAM_B)
35
36
37 left.requestOutput((width, height)).link(stereo.left)
38 right.requestOutput((width, height)).link(stereo.right)
39 stereo.syncedLeft.link(odom.left)
40 stereo.syncedRight.link(odom.right)
41 stereo.depth.link(slam.depth)
42 stereo.rectifiedLeft.link(slam.rect)
43 imu.out.link(odom.imu)
44
45 odom.transform.link(slam.odom)
46 slam.transform.link(rerunViewer.inputTrans)
47 slam.passthroughRect.link(rerunViewer.inputImg)
48 slam.occupancyGridMap.link(rerunViewer.inputGrid)
49 slam.obstaclePCL.link(rerunViewer.inputObstaclePCL)
50 slam.groundPCL.link(rerunViewer.inputGroundPCL)
51 p.start()
52 while p.isRunning():
53 time.sleep(1)
Need assistance?
Head over to Discussion Forum for technical support or any other questions you might have.