相机标定
相机内参标定
主要有两种方式
kalib
生成标定棋格盘
查看帮助
kalibr_create_target_pdf --h kalibr_create_target_pdf --type apriltag --nx [NUM_COLS] --ny [NUM_ROWS] --tsize [TAG_WIDTH_M] --tspace [TAG_SPACING_PERCENT]
生成A4纸棋盘内部角点个数6x7棋盘格,边长0.030m,打印的时候选择实际大小,否则打印出来的格子可能比较小.可能需要安装模块
sudo apt-get install python-pyx
kalibr_create_target_pdf --type checkerboard --nx 6 --ny 7 --csx 0.030 --csy 0.030
录制bag包
首先运行相机驱动可以更改相机话题和频率
rosrun topic_tools throttle messages /camera/color/image_raw 4.0 /color
录制图像
rosbag record -O camd435 /color
标定
一种是使用kalibr_calibrate_cameras
标定生成
checkerboard.yaml
文件target_type: 'checkerboard' #gridtype targetCols: 6 #number of internal chessboard corners targetRows: 7 #number of internal chessboard corners rowSpacingMeters: 0.03 #size of one chessboard square [m] colSpacingMeters: 0.03 #size of one chessboard square [m]
标定
kalibr_calibrate_cameras --target path/to/checkerboard.yaml --bag path/to/camd435i.bag --models pinhole-equi --topics /color --show-extractio
另一种是使用matlab工具箱标定
%% 读取bag文件 bag = rosbag('camd435.bag'); geometry_message = select(bag,'Topic','/color'); data = readMessages(geometry_message); imshow(readImage(data{1, 1})); % 显示图片 % 保存图片 for i = 1 : length(data) im_data = readImage(data{i, 1}); imwrite(im_data, [num2str(i), '.png']); end %% matlab 工具箱Camera Calibrator(在app里面搜索然后导入图片) 标定后可以生成代码
camera-calibration
安装标定包
sudo apt-get install ros-kinetic-camera-calibration
运行标定程序
会有一个GUI方便操作,将棋盘对着相机朝着左/右/上/下/前/后移动,还需要倾斜棋盘。绿色填满之后点击CALIBRATE按钮,需要等几分钟. 生成的文件在/tmp/calibrationdata.tar.gz
中rosrun camera_calibration cameracalibrator.py --size 6x7 --square 0.03 image:=/image_raw camera:=/camera
获取标定结果
cd /tmp tar -xvzf calibrationdata.tar.gz mv ost.txt ost.ini # 得到camera.yaml rosrun camera_calibration_parsers convert ost.ini camera.yaml
相机外参标定(手眼标定)
这篇文章的图片已经解释的很清楚了机器人手眼标定Ax=xB(eye to hand和eye in hand)及平面九点法标定
- eye-in-hand
两次运动,机器人底座和标定板的位恣关系不变,求解相机和机器人末端的位姿关系
- eye-on-base
两次运动,机器人末端和标定板的位恣关系不变,求解相机和机器人基座之间的位恣关系
franka realsense 标定
主要使用了三个包:
- aruco_ros, 相机获取二维码位恣,二维码可通过ArUco markers generator!生成,记得一定要选择Original ArUco
ID和size根据需要选择,这两个参数在之后的launch文件中使用,这里选用的是ID:582,size:50 - easy_handeye, 结合moveit标定的包
- realsense-ros, realsense ros驱动
则有标定launch文件如下,标定后得到camera_link到panda_link0的位恣变换,然后在launch文件中使用tf2_ros中的static_transform_publisher发布出来即可使用
<?xml version="1.0" ?>
<launch>
<!-- franka -->
<arg name="robot_ip" default="192.168.10.102"/>
<arg name="move_group" default="panda_arm" />
<arg name="robot_base_frame" default="panda_link0"/>
<arg name="robot_effector_frame" default="panda_EE"/>
<!-- marker -->
<arg name="markerId" default="582"/>
<arg name="markerSize" default="0.05"/> <!-- in m -->
<arg name="marker_frame" default="aruco_marker_frame"/>
<arg name="ref_frame" default="camera_link"/> <!-- leave empty and the pose will be published wrt param parent_name -->
<arg name="camera_frame" default="camera_color_optical_frame"/>
<arg name="corner_refinement" default="LINES" /> <!-- NONE, HARRIS, LINES, SUBPIX -->
<!-- launch franka -->
<include file="$(find franka_control)/launch/franka_control.launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
<arg name="load_gripper" value="true" />
</include>
<include file="$(find panda_moveit_config)/launch/panda_moveit.launch">
<arg name="load_gripper" value="true" />
</include>
<!-- panda_link0 to world TF -->
<node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_1" args="0 0 0 0 0 0 world panda_link0" />
<!-- realsense -->
<include file="$(find realsense2_camera)/launch/rs_camera.launch"/>
<!-- marker -->
<node pkg="aruco_ros" type="single" name="aruco_single">
<remap from="/camera_info" to="/camera/color/camera_info" />
<remap from="/image" to="/camera/color/image_raw" />
<param name="image_is_rectified" value="True"/>
<param name="marker_size" value="$(arg markerSize)"/>
<param name="marker_id" value="$(arg markerId)"/>
<param name="reference_frame" value="$(arg ref_frame)"/> <!-- frame in which the marker pose will be refered -->
<param name="camera_frame" value="$(arg camera_frame)"/>
<param name="marker_frame" value="$(arg marker_frame)" />
<param name="corner_refinement" value="$(arg corner_refinement)" />
</node>
<node pkg="image_view" type="image_view" name="iamge_view" args="image:=/aruco_single/result" />
<!-- easy hand eye calibrate -->
<include file="$(find easy_handeye)/launch/calibrate.launch">
<arg name="eye_on_hand" value="false"/>
<arg name="move_group" value="$(arg move_group)" />
<!-- fill in the following parameters according to your robot's published tf frames -->
<arg name="robot_base_frame" value="$(arg robot_base_frame)"/>
<arg name="robot_effector_frame" value="$(arg robot_effector_frame)"/>
<!-- fill in the following parameters according to your tracking system's published tf frames -->
<arg name="tracking_base_frame" value="$(arg ref_frame)"/>
<arg name="tracking_marker_frame" value="$(arg marker_frame)"/>
</include>
</launch>
遇到的问题:
import cv2的版本不对(
pip3 install opencv-python
pip install opencv-contrib-python
安装位置在~/.local下)# 查看cv2的路径 发现对的cv2在~/.local下 import cv2 help(cv2) # 是cv2.so文件 可以通过locate定位(根据需要进行updatedb) # 查看python path信息 import sys sys.path # '/opt/ros/kinetic/lib/python2.7/dist-packages'在前面, 而对的cv2在~/.local,排在后面 # 在需要用到cv2的地方如下处理即可 import sys sys.path.remove('/opt/ros/kinetic/lib/python2.7/dist-packages') import cv2 sys.path.append('/opt/ros/kinetic/lib/python2.7/dist-packages')
无法显示rqt_gui界面的gui操作框
可能是由于conda环境冲突,切换回系统对应的环境就可以了(最开始是把libqt5*卸载之后再安装依赖就可以,之后发现还是得切换回之前的环境)相机对反光敏感
相机外参标定好之后在rviz中查看点云,人站在相机正前方走动会产生其它地方的点云(机械臂附近),造成干扰
引用
- 机器人手眼标定Ax=xB(eye to hand和eye in hand)及平面九点法标定
- 3D 视觉之手眼标定
- 通过ROS控制真实机械臂(15) —- 视觉抓取之手眼标定
- Inter Realsense D435i标定过程步骤记录(超详细)
- 视觉SLAM | RealsenseD435i相机标定
转载请注明来源,欢迎对文章中的引用来源进行考证,欢迎指出任何有错误或不够清晰的表达。可以邮件至 yangbenbo@whu.edu.cn
文章标题:相机标定
本文作者:杨本泊
发布时间:2020-12-26, 14:54:40
最后更新:2023-07-09, 07:10:12
原始链接:http://yangbenbo.github.io/2020/12/26/相机标定/版权声明: "署名-非商用-相同方式共享 4.0" 转载请保留原文链接及作者。