appliedAI-Initiative / orb_slam_2_ros

A ROS implementation of ORB_SLAM2
Other
614 stars 281 forks source link

working with stereo camera #61

Open D7823 opened 4 years ago

D7823 commented 4 years ago

Hi,

I am working with a stereo camera and firstly simply fed the video and the calibration file (with all those D, K, R, P parameter in). According to previous issues, the orb_slam should do the image rectification for me but I found that it seems like the image was not rectified from the shown debug_image. There was very few features extracted from every frame and almost no tracking actually happened during the SLAM process. I then used the image_proc node to rectify the images and fed the rectified image to orb_slam. This time, it was able to get more features and build a map a bit. So I think I am not actually getting the rectification function in the orb_slam working, is there anything I also need to add/modifier besides putting those intrinsic parameters into the calibration file?

Thanks in advance. Duncan

lennarthaller commented 4 years ago

Thank you for reporting this. #42 seems to be the same issue. Unfortunately I don't have a stereo camera available to me right now. It is very possible that there is a bug or even rectification code missing as I have never tested rectifying the images with this package. Please share any information you get from you investigation here.

All the best, Lennart

clydemcqueen commented 3 years ago

I did some investigations with stereo cameras, and learned a few things.

Node.cc subscribes to a single camera info message (you can choose left or right), so whatever calibration info you provide will be used to undistort the points in both the left and right cameras. I played around with simulations, and if both cameras have the exact same D parameters it works well, but of course with real cameras the results will be less good.

orb_slam2_ros ignores the rectification info in R. The only info used in the camera_baseline parameter. I'm using 2 cameras to build a stereo pair, and rectifying the images improved the results for me.

A reasonable workaround is to undistort and rectify the images using image_proc or something similar and have orb_slam2_ros subscribe to the rectified images. You also need to provide modified camera info that does not include the distortion parameters, and to get good scaling the modified camera info should pull fx, fy, cx and cy values from P, not K. Or you can modify Node.cc to do the same thing in code. I did this across 2 commits: https://github.com/clydemcqueen/orb_slam_2_ros/commit/bd7c9eed45529cf303573c431ba47bb7c264043a https://github.com/clydemcqueen/orb_slam_2_ros/commit/acb5bf768b349c0b70266f76038cb405a493913d

I've been doing work with ros2, but I suspect that the same is true with ros1 as well.

I'd love to have other eyes on this.

Thanks, /Clyde