Ubuntu Development System Configuration
- OpenCV
- PCL
- ROS
- Qt
- Flycapture
- Triclops
- ZJU-Repository Mirror Source
Stereo Camera Calibration
$ rosrun camera_calibration cameracalibrator.py --size 12x9 --square 0.05 right:=/camera/right/image_raw left:=/camera/left/image_raw right_camera:=/camera/right left_camera:=/camera/left
注:其中,12x9表示标定板横向和纵向的角点数;0.05表示标定板格子的边长,单位是米。
标定前效果:
标定后效果:
launch bumblebee2 stereo camera
$ roslaunch pointgrey_camera_driver bumblebee.launch
如下是一个可用的bumblebee.launch
<launch>
<!-- Determine this using rosrun pointgrey_camera_driver list_cameras.
If not specified, defaults to first camera found. -->
<arg name="bumblebee_serial" default="0" />
<arg name="calibrated" default="1" />
<group ns="camera">
<node pkg="nodelet" type="nodelet" name="bumblebee_nodelet_manager" args="manager" />
<node pkg="nodelet" type="nodelet" name="bumblebee_nodelet"
args="load pointgrey_camera_driver/PointGreyStereoCameraNodelet bumblebee_nodelet_manager" >
<param name="frame_id" value="bumblebee" />
<param name="frame_rate" value="15" />
<param name="first_namespace" value="left" />
<param name="second_namespace" value="right" />
<!-- When without this statement, the image publishing activity may be wrong. -->
<param name="format7_color_coding" value="raw16" />
<param name="serial" value="$(arg bumblebee_serial)" />
<!-- Use the camera_calibration package to create these files -->
<param name="camera_info_url" if="$(arg calibrated)"
value="file://$(env HOME)/.ros/camera_info/bb208s2c38_left.yaml" />
<param name="second_info_url" if="$(arg calibrated)"
value="file://$(env HOME)/.ros/camera_info/bb208s2c38_right.yaml" />
</node>
<node pkg="nodelet" type="nodelet" name="image_proc_debayer_left"
args="load image_proc/debayer bumblebee_nodelet_manager">
<remap from="image_raw" to="left/image_raw"/>
<remap from="image_mono" to="left/image_mono"/>
<remap from="image_color" to="left/image_color"/>
</node>
<node pkg="nodelet" type="nodelet" name="image_proc_debayer_right"
args="load image_proc/debayer bumblebee_nodelet_manager">
<remap from="image_raw" to="right/image_raw"/>
<remap from="image_mono" to="right/image_mono"/>
<remap from="image_color" to="right/image_color"/>
</node>
</group>
</launch>
注1:bb208s2c38_left.yaml和bb208s2c38_right.yaml分别是双目相机的标定文件。
注2:默认的bumblebee.launch如果没有指定Bumblebee2相机图像的格式,这可能导致ROS无法持续采集图像。
run stereo_image_proc node
$ ROS_NAMESPACE=camera rosrun stereo_image_proc stereo_image_proc
注:务必指定名字空间,以确保节点订阅到正确的话题。
查看视差图像:
$ rosrun image_view disparity_view image:=/camera/disparity
run libviso2 node
$ rosrun viso2_ros stereo_odometer stereo:=camera image:=image_rect
注:务必正确映射名字空间。
$ roslaunch '/home/robot/catkin_ws/src/drivers/pointgrey_camera_driver-master/fake_tf.launch'
注:此句是为了坐标变换。
ORB-SLAM2
- run ORB-SLAM2 Monocular node
$ rosrun ORB_SLAM2 Mono /home/exbot/robot/ORB_SLAM2-master/Vocabulary/ORBvoc.txt /home/exbot/robot/ORB_SLAM2-master/Examples/Monocular/xtion_as_mono.yaml /camera/image_raw:=/camera/rgb/image_rect_color
注1:Take Xtion’ s rgb channel as mono.
注2:由此可见,重映射话题名是个很容易的事情,可以在.launch文件中用标签指示,可以在命令行直接赋值,也可以在节点源文件中指定函数参数。
如下是一个可用的xtion_as_mono.yaml
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 518.0236
Camera.fy: 515.6649
Camera.cx: 316.4371
Camera.cy: 247.8384
Camera.k1: 0.0219
Camera.k2: -0.1336
Camera.p1: 0.0079
Camera.p2: -0.0043
Camera.k3: 0
# Camera frames per second
Camera.fps: 30.0 # If you want to get this value, you can test it with 'rostopic hz'
# Yes, it is almost 30Hz.
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000
# 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
- run ORB-SLAM2 Stereo node
$ rosrun ORB_SLAM2 Stereo /home/exbot/robot/ORB_SLAM2-master/Vocabulary/ORBvoc.txt /home/exbot/robot/ORB_SLAM2-master/Examples/Stereo/bb2.yaml false
注1:Take Bumblebee2-08S2C38 as sensor.
注2:这里最后一个参数false表示所订阅的左右图像已经是校正过的了,也就不需要根据bb2.yaml中的畸变参数进行校正了。
驱动 Hokuyo UTM-30LX-EW(Ethernet)
首先,安装驱动包,命令如下:
$ sudo apt-get install ros-indigo-urg-node
然后,配置主机的IP地址,与Hokuyo的IP处于同一局域网即可,例如:192.168.0.2。
至此,就可以运行驱动程序了,命令如下:
$ rosrun urg_node urg_node _ip_address:="192.168.0.10"
注:这里,指定了hokuyo的IP地址。
本部分参考链接