ZED2+ORB_SLAM3

31 篇文章 0 订阅
18 篇文章 0 订阅

仿照/ORB_SLAM3/Examples/ROS/ORB_SLAM3/src目录下的ros_stereo.cc建立一个新文件,如zed2_stereo_inertial.cc。将代码复制过去,修改以下部分:

  ros::Subscriber sub_imu = n.subscribe("/imu", 1000, &ImuGrabber::GrabImu, &imugb); 
  ros::Subscriber sub_img_left = n.subscribe("/camera/left/image_raw", 100, &ImageGrabber::GrabImageLeft,&igb);
  ros::Subscriber sub_img_right = n.subscribe("/camera/right/image_raw", 100, &ImageGrabber::GrabImageRight,&igb);

改为:

  ros::Subscriber sub_imu = n.subscribe("/zed/zed_node/imu/data", 1000, &ImuGrabber::GrabImu, &imugb); 
  ros::Subscriber sub_img_left = n.subscribe("/zed/zed_node/left/image_rect_color", 100, &ImageGrabber::GrabImageLeft,&igb);
  ros::Subscriber sub_img_right = n.subscribe("/zed/zed_node/right/image_rect_color", 100, &ImageGrabber::GrabImageRight,&igb);

此处选取了ZED2的三个数据流,IMU数据,左目数据和右目数据

然后修改CmakeLists.txt,仿照加入:

# Node for ZED camera
rosbuild_add_executable(ZED_Stereo_IMU
src/zed2_stereo_inertial.cc
)

target_link_libraries(ZED_Stereo_IMU
${LIBS}
)

重新编译

./build_ros.sh

会新生成一个可执行文件 ZED_Stereo_IMU.yaml
在其中添加

%YAML:1.0

#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
Camera.type: "PinHole"

# Camera calibration and distortion parameters (OpenCV) (equal for both cameras after stereo rectification)
Camera.fx: 528.3009033203125
Camera.fy: 528.3009033203125
Camera.cx: 632.7931518554688
Camera.cy: 372.5525817871094

# 用的是校正过的节点,所以畸变参数设置为0
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0

Camera.width: 1280
Camera.height: 720

# Camera frames per second 
Camera.fps: 15.0

# stereo baseline times fx
Camera.bf: 63.396108984375

# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1

# Close/Far threshold. Baseline times.
ThDepth: 40.0 # 35

# Transformation from camera 0 to body-frame (imu)
# 从左目转换到IMU坐标系
Tbc: !!opencv-matrix
   rows: 4
   cols: 4
   dt: f
   data: [ 0.0055827285742915,  0.0128040922714603,  0.9999024394223516,  0.0285440762197234,
          -0.9999801332587812,  0.0029981004108222,  0.0055447706603969, -0.1038871459045697,
          -0.0029268121592544, -0.9999135295689473, 0.0128205754767047, -0.0063514683297355,
           0.0000000000000000, -0.0000000000000000, -0.0000000000000000,  1.0000000000000000]

# IMU noise
# get it from Project of **zed-examples/tutorials/tutorial 7 - sensor data/**.
IMU.NoiseGyro: 0.007 # 1.6968e-04 
IMU.NoiseAcc:  0.0016 # 2.0000e-3
IMU.GyroWalk:  0.0019474 
IMU.AccWalk:   0.0002509 # 3.0000e-3
IMU.Frequency: 400

#--------------------------------------------------------------------------------------------
# Stereo Rectification. Only if you need to pre-rectify the images.
# Camera.fx, .fy, etc must be the same as in LEFT.P
#--------------------------------------------------------------------------------------------
LEFT.height: 720
LEFT.width: 1280
LEFT.D: !!opencv-matrix
   rows: 1
   cols: 5
   dt: d
   data: [0, 0, 0, 0, 0]
LEFT.K: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [528.3009033203125, 0.0, 632.7931518554688, 0.0, 528.3009033203125, 372.5525817871094, 0.0, 0.0, 1.0]
LEFT.R:  !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
LEFT.Rf:  !!opencv-matrix
   rows: 3
   cols: 3
   dt: f
   data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
LEFT.P:  !!opencv-matrix
   rows: 3
   cols: 4
   dt: d
   data: [528.3009033203125, 0.0, 632.7931518554688, 0.0, 0.0, 528.3009033203125, 372.5525817871094, 0.0, 0.0, 0.0, 1.0, 0.0]

RIGHT.height: 720
RIGHT.width: 1280
RIGHT.D: !!opencv-matrix
   rows: 1
   cols: 5
   dt: d
   data: [0, 0, 0, 0, 0]
RIGHT.K: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [528.3009033203125, 0.0, 632.7931518554688, 0.0, 528.3009033203125, 372.5525817871094, 0.0, 0.0, 1.0]
RIGHT.R:  !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
RIGHT.P:  !!opencv-matrix
   rows: 3
   cols: 4
   dt: d
   data: [528.3009033203125, 0.0, 632.7931518554688, -63.47084045410156, 0.0, 528.3009033203125, 372.5525817871094, 0.0, 0.0, 0.0, 1.0, 0.0]

#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------

# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1200

# ORB Extractor: Scale factor between levels in the scale pyramid 	
ORBextractor.scaleFactor: 1.2

# ORB Extractor: Number of levels in the scale pyramid	
ORBextractor.nLevels: 8

# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast			
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7

#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500

在/ORB_SLAM3/Examples/Stereo-Inertial下创建Stereo_IMU.yaml

然后

命令行
cd ~/catkin_ws
source ./devel/setup.bash
roscore

//另开一个命令行
cd ~/catkin_ws
source ./devel/setup.bash //不知道为什么不执行这一步就无法找到zed.launch
roslaunch zed_wrapper zed.launch

//另开一个命令行
cd ~/catkin_ws/src/ORB_SLAM3
rosrun ORB_SLAM3 ZED_Stereo_IMU Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/Stereo_IMU.yaml false
  • 0
    点赞
  • 8
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 6
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 6
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

Gone_float

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值