基于ROS的双目摄像头的标定
木木千雅 2024-09-18 11:31:01 阅读 69
写在前面:
完全可复现
双目摄像头为成品,某宝链接:
<code>https://item.taobao.com/item.htm?_u=23ccdrc3141a&id=680371983853&skuId=4872591496821&spm=a1z09.2.0.0.67002e8dCVqvVh
前提
安装好OpenCV和ros1,OpenCV安装教程百度一堆,我的版本如下:
Python 3.8.10 (default, Jul 29 2024, 17:02:10)
[GCC 9.4.0] on linux
Type "help", "copyright", "credits" or "license" for more information.
>>> import cv2
>>> cv2.__version__
'4.7.0'
1、ROS安装
参考小鱼的一键安装:小鱼的一键安装系列 | 鱼香ROS
wget http://fishros.com/install -O fishros && . fishros
2、安装相机相关功能包
创建工作空间
mkdir -p catkin_ws/src
cd catkin_ws
catkin_make
source devel/setup.bash
安装usb_cam(注意ROS版本)
sudo apt install ros-noetic-usb-cam*
编译启动相机测试一下:
启动前先写个launch文件:
其实内容就是/opt/ros/noetic/share/usb_cam/launch/usb_cam-test.alunch的内容,改分辨率为1280*480
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >code>
<param name="video_device" value="/dev/video0" />code>
<param name="image_width" value="1280" />code>
<param name="image_height" value="480" />code>
<param name="pixel_format" value="yuyv" />code>
<param name="color_format" value="yuv422p" />code>
<param name="camera_frame_id" value="usb_cam" />code>
<param name="io_method" value="mmap"/>code>
</node>
<node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">code>
<remap from="image" to="/usb_cam/image_raw"/>code>
<param name="autosize" value="true" />code>
</node>
</launch>
效果如下
看下rostopic
显然↓
可以看到,集成到一个画面,而且rostopic list只有一个话题名称(问题的关键就是找到关键问题——单接口双目一个话题分割为两个话题,方便标定)
3、写分割节点,重写launch文件
分割节点命名为image_splitter.py
位置在catkin_ws/scripts/image_splitter.py,工作空间的文件树如下:
<code>.
├── AUTHORS.md
├── CHANGELOG.rst
├── CMakeLists.txt
├── config
│ └── usb_cam.yml
├── include
│ └── usb_cam
│ ├── camera_driver.h
│ ├── converters.h
│ ├── types.h
│ ├── usb_cam.h
│ └── util.h
├── launch
│ ├── test_img_view.launch
│ ├── usb_cam.launch
│ └── usb_cam-test.launch
├── LICENSE
├── mainpage.dox
├── package.xml
├── README.md
├── scripts
│ └── image_splitter.py
└── src
├── camera_driver.cpp
├── converters.cpp
├── LICENSE
├── usb_cam.cpp
├── usb_cam_node.cpp
└── util.cpp
image_splitter.py具体内容如下:
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
def callback(data):
bridge = CvBridge()
try:
cv_image = bridge.imgmsg_to_cv2(data, "bgr8")
height, width, _ = cv_image.shape
left_image = cv_image[:, :width//2]
right_image = cv_image[:, width//2:]
left_image_msg = bridge.cv2_to_imgmsg(left_image, "bgr8")
right_image_msg = bridge.cv2_to_imgmsg(right_image, "bgr8")
left_pub.publish(left_image_msg)
right_pub.publish(right_image_msg)
except CvBridgeError as e:
rospy.logerr(e)
if __name__ == '__main__':
rospy.init_node('image_splitter', anonymous=True)
left_pub = rospy.Publisher('/usb_cam_left/image_raw', Image, queue_size=10)
right_pub = rospy.Publisher('/usb_cam_right/image_raw', Image, queue_size=10)
rospy.Subscriber('/usb_cam/image_raw', Image, callback)
rospy.spin()
sudo chmod +x image_splitter.py
在usb_cam功能包下的CMakelist中添加:
catkin_install_python(PROGRAMS
scripts/image_splitter.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
更改usb_cam-test.launch文件内容,如下:
这里的分辨率我直接把横向*2,比如正常1280*720,更改后就应该是2560*720
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >code>
<param name="video_device" value="/dev/video0" />code>
<param name="image_width" value="1280" />code>
<param name="image_height" value="480" />code>
<param name="pixel_format" value="yuyv" />code>
<param name="color_format" value="yuv422p" />code>
<param name="camera_frame_id" value="usb_cam" />code>
<param name="io_method" value="mmap"/>code>
</node>
<node name="image_splitter" pkg="usb_cam" type="image_splitter.py" output="screen" />code>
<node name="image_view_left" pkg="image_view" type="image_view" respawn="false" output="screen">code>
<remap from="image" to="/usb_cam_left/image_raw"/>code>
<param name="autosize" value="true" />code>
</node>
<node name="image_view_right" pkg="image_view" type="image_view" respawn="false" output="screen">code>
<remap from="image" to="/usb_cam_right/image_raw"/>code>
<param name="autosize" value="true" />code>
</node>
</launch>
编译工作空间:
cd ~/catkin_ws
# 因为安装了conda,导致python位置会指向conda的base环境,
#可以conda deactivate,也可以指定python位置
catkin_make -DPYTHON_EXECUTABLE=/usr/bin/python3
#当前窗口内容生效
source devel/setup.bash
4、启动看看
roslaunch usb_cam usb_cam-test.launch
效果和话题如下
暂时搞定单接口双目摄像头的图像分割和话题分割。
这里就有疑问,为啥费劲巴拉的要分割,因为ROS Wiki给的双目标定是俩话题,其他类似OpenCV的双目标定也是两个摄像头的画面分割后的标定。
具体参考下面章节内容↓
5、通过ROS标定
参考:camera_calibration/Tutorials/StereoCalibration - ROS Wiki
ROS官网提供这个参考其实更适用于两个单独的摄像头组合的双目系统(更适合手搓),因为是单接口双目系统,在此基础上需要做一些改变
先安装标定工具箱
注:使用小鱼的一键安装ROS,使用rosdep时命令改为rosdepc
<code>rosdepc install camera_calibration
rosmake camera_calibration
前面已经把双目系统的画面分割开,使得话题有两个,但是双目系统的camera_info是一样的;另外,ROS Wiki是以ROS node的形式执行,这里改写成一个launch文件,同时执行前面的分割和标定工具箱
cd catkin_ws/launch
touch camera_calibration.launch
camera_calibration.launch内容如下:
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen">code>
<param name="video_device" value="/dev/video0" />code>
<param name="image_width" value="1280" />code>
<param name="image_height" value="480" />code>
<param name="pixel_format" value="yuyv" />code>
<param name="color_format" value="yuv422p" />code>
<param name="camera_frame_id" value="usb_cam" />code>
<param name="io_method" value="mmap"/>code>
</node>
<node name="image_splitter" pkg="usb_cam" type="image_splitter.py" output="screen" />code>
<node name="camera_calibrator" pkg="camera_calibration" type="cameracalibrator.py" output="screen" args="--approximate 0.1 --size 7x6 --square 0.1 right:=/usb_cam_right/image_raw left:=/usb_cam_left/image_raw right_camera:=/usb_cam left_camera:=/usb_cam" />code>
</launch>
注意:最后两行的参数--size 7x6是棋盘格交叉点个数,--square 0.1是方格边长0.1m,根据自己棋盘格适当更改,没有棋盘格的,上面ROS Wiki有
编译工作空间,同时使得窗口生效
#此时命令行应该是在launch文件夹下,退回上一层,也就是catkin_ws
cd ..
catkin_make
source devel/setup.bash
执行launch进行标定:
#热知识,roslaunch命令会启动rosmaster,不需要执行roscore
roslaunch usb_cam camera_calibration.launch
上下左右旋转平移移动标定板位置和角度直到右边进度条跑满即可。
点击COMMIT将校准参数发送到相机进行永久存储,点击SAVE保存校准参数和校准中使用的图像,所有内容都将默认保存在压缩文件夹 /tmp/calibrationdata.tar.gz 中!
本来想基于双目实现yolov8的目标检测和测距,但卡在标定,还是花一天时间来想解决方案。本来想用autoware一键搞定,但是有点为难nano了,有一台设备安装好了autoware远程又掉线(md,好烦),又不想拍照片再python脚本分割,于是想着采用ROS来标定。挖个坑,下一步将进行
1.基于OpenCV的深度估计(测距)
2.基于YOLOv8+sgbm的目标检测和测距
声明
本文内容仅代表作者观点,或转载于其他网站,本站不以此文作为商业用途
如有涉及侵权,请联系本站进行删除
转载本站原创文章,请注明来源及作者。