ORB-SLAM跑通注意事项
ORB-SLAM跑通注意事项
系统版本:Ubuntu 14.04
ROS版本:ROS indigo
ORB-SLAM项目主页
ORB-SLAM源码
源码中的README,已经将源码怎样编译,怎样运行都讲的很仔细明白了。另,已经有博主漫游者1号的博文ORB-SLAM(1) — 让程序飞起来也有详细的讲解,我就不再写在这里了。不过,编译运行的过程中,我还遇到了一些问题,记录如下:
- 如果ROS使用的版本是Indigo,那么就不需要OpenCV2依赖了,将manifest.xml中的
<depend package="opencv2"/>
注释掉或删掉就可以了。 - 编译安装之前,将ORB-SLAM的路径加到环境变量ROS_PACKAGE_PATH中。
vim ~/.bashrc
# 在末尾添加上如下语句
# 其中PATH_TO_PARENT_OF_ORB_SLAM是ORB_SLAM工程项目文件夹的绝对路径
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:PATH_TO_PARENT_OF_ORB_SLAM
# bashrc修改后
source ~/.bashrc
- 在终端运行ORB_SLAM时,要先执行
roscore
,然后执行下面这条语句rosrun ORB_SLAM ORB_SLAM Data/ORBvoc.txt Data/Settings.yaml
参数使用的是相对路径。至于为什么使用相对路径,是因为源码中是如下方式载入设置文件与ORB词汇文件的(当然,你可以自己修改代码):
...
// Load Settings and Check
string strSettingsFile = ros::package::getPath("ORB_SLAM")+"/"+argv[2];
...
string strVocFile = ros::package::getPath("ORB_SLAM")+"/"+argv[1];
ORB_SLAM::ORBVocabulary Vocabulary;
bool bVocLoad = Vocabulary.loadFromTextFile(strVocFile);
...
- ROS打开摄像头,需要安装和摄像头相对应的驱动,如uvc摄像头
sudo apt-get install ros-indigo-uvc-camera
,usb摄像头sudo apt-get install ros-indigo-usb-cam
。然后,执行source /opt/ros/indigo/setup.bash
。不知道摄像是什么型号的,可以使用命令lsusb
查看一下。
安装完相应的驱动后,就可以使用如下命令打开摄像头了:
# usb摄像头
rosrun usb_camera usb_camera_node
rosrun image_view image_view image:=/image _autosize:=true
# uvc摄像头
rosrun uvc_camera uvc_camera_node
rosrun image_view image_view image:=/image_raw _autosize:=true
# image:=/topic 后面的topic可以使用如下命令查看,换成你的环境中的topic
rostopic list
- 但是,以上打开的总是笔记本本地的摄像头,始终无法启动usb摄像头。解决方法是,写一个open_usbcam.launch文件,其中video_device的value指定为usb摄像头的挂载路径及文件名(我的是/dev/video1,ls /dev查看以下即可)。
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video1" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
</node>
<node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">
<remap from="image" to="/usb_cam/image_raw"/>
<param name="autosize" value="true" />
</node>
</launch>
然后,按照如下的步骤运行ORB_SLAM:
# 运行ros
roscore
# 打开摄像头
roslaunch open_usbcam.launch
# 运行ORB_SLAM
rosrun ORB_SLAM ORB_SLAM Data/ORBvoc.txt Data/Settings.yaml
# 显示跟踪画面
rosrun image_view image_view iamge:=/ORB_SLAM/Frame _autosize:=true
# 显示建图画面(ros indigo)
rosrun rviz rviz -d Data/rviz.rviz
- 结果发现rviz的image画面总是没有图像出现,README中提到ORB_SLAM是从主题/camera/image_view中获取图像的。修改open_usbcam.launch,将图像重新映射到该主题下显示,结果还是没有图像出现(不知道是不是因为没有修改对,我得去看看ROS的使用教程了,之前都是照着例子和感觉改的)。github中ORB_SLAM项目下的Issuses中有人提到了该问题rosrun image_view #42,其中jwcrawley给出的方法,解决了我的问题。修改ExampleGroovyOrNewer.launch如下:
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video1" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="camera" />
<param name="io_method" value="mmap"/>
<remap from="/usb_cam/image_raw" to="/camera/image_raw" />
</node>
<node pkg="image_view" type="image_view" name="image_view" respawn="false" output="log">
<remap from="/image" to="/ORB_SLAM/Frame" />
<param name="autosize" value="true"/>
</node>
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find ORB_SLAM)/Data/rviz.rviz" output="log">
</node>
<node pkg="ORB_SLAM" type="ORB_SLAM" name="ORB_SLAM" args="Data/ORBvoc.txt Data/Settings.yaml" cwd="node" output="screen">
</node>
</launch>
以后直接运行roslaunch ExampleGroovyOrNewer.launch
即可。