ROS手眼标定简明教程
简介
手眼标定(Hand-eye Calibration)是机器人技术中的一个关键步骤,用于确定机器人末端执行器(手)和相机(眼)之间的准确转换关系。这种转换关系通常表示为一个齐次变换矩阵,将相机坐标系的点与机器人基坐标系的点进行映射。手眼标定的目标是获取这个变换矩阵,以便机器人正确地感知并操作其周围的环境。
标定类型
手眼标定根据相机的安装方式,分为两种类型。
1)眼在手外(Eye to hand) :相机和机械臂分离,需要确认相机坐标系和机器人的基坐标系之间的转换关系。
2)眼在手上(Eye in hand):相机在机械臂上,需要确认相机坐标系和机器人的末端之间的转换关系。
位姿描述
机器人视为符合刚体的数学模型,三维空间中的刚体一共有六个空间自由度,包括三个平移坐标和三个旋转坐标,即位置自由度和姿态自由度。通过对机器人在空间中的位姿描述得到机械臂末端相对于基座的位置和姿态。通过ROS的tf库将摄像头外参矩阵发布到ROS当中,建立相机到base_link的TF树,此时只需要获取目标到相机坐标,然后通过订阅TransformListener实现坐标转换。
标定原理
用相机从多个不同的方位对标定板进行拍摄,并记录机器人在这些位置的姿态参数,利用机器人姿态参数以及不同位置的矩阵信息可以推导出关于旋转矩阵R和平移向量T的若干个关系方程,手眼标定即求解R,T关系方程组的过程。
标定流程
首先建立机器人基座坐标系到相机坐标系的转换关系,再通过手眼标定获取转换矩阵,最后求解得到相机坐标系和机器人末端坐标系的转换关系。选用 ROS的 easy_handeye 包以及 Aruco_ros 进行标定,通过该方法获取到摄像头到机械臂的外参矩阵。
easy_handeye功能包
easy_handeye 是一个简化手眼标定过程的库,提供了多种标定算法,旨在提高标定的精度和可靠性,使得视觉系统和机器人控制系统之间的协调更加精准。
git clone https://github.com/IFL-CAMP/easy_handeye.git
记得安装功能包所需要的依赖。
aruco_ros功能包
aruco_ros是一个用于检测和识别aruco标记marker的库。这些标记类似于二维码,通过相机能够识别和解码,我们需要使用aruco标记作为标定的参考。aruco_ros能够实时检测这些标记并提供其在图像中的位姿信息,支持多种标记类型和尺寸,为机器人提供精准的视觉引导和定位能力。
git clone -b noetic-devel https://github.com/pal-robotics/aruco_ros.git
进入aruco marker生成网站https://chev.me/arucogen/打印用于标定的marker,注意选择字典为original,记住自己选择的Marker ID和尺寸。
除此之外,还需要在工作空间下编译好机器人和相机的ROS功能包。
修改配置文件
在easyhandeye功能包下的easy_handeye/launch路径下添加一个新的launch 启动配置文件,示例如下(本人使用的是睿尔曼的RM65B机械臂与realsense-d415相机):
<?xml version="1.0"?>
<launch>
<arg name="namespace_prefix" default="handeyecalibration" />
<arg name="marker_size" doc="Size of the ArUco marker used, in meters" default="0.10"/>
<arg name="marker_id" doc="The ID of the ArUco marker used" default="150"/>
<!-- start the robot -->
<include file="$(find rm_bringup)/launch/rm_65_robot.launch">
</include>
<!--start realsense-->
<include file="$(find realsense2_camera)/launch/rs_camera.launch">
<arg name="filters" value="pointcloud"/>
</include>
<!-- start ArUco -->
<node name="aruco_tracker" pkg="aruco_ros" type="single" output="screen">
<remap from="/camera_info" to="/camera/aligned_depth_to_color/camera_info" />
<remap from="/image" to="/camera/color/image_raw" />
<param name="image_is_rectified" value="true"/>
<param name="marker_size" value="$(arg marker_size)"/>
<param name="marker_id" value="$(arg marker_id)"/>
<param name="reference_frame" value="camera_color_optical_frame"/>
<param name="camera_frame" value="camera_color_optical_frame"/>
<param name="marker_frame" value="object_marker" />
</node>
<!-- start easy_handeye -->
<include file="$(find easy_handeye)/launch/calibrate.launch" >
<arg name="namespace_prefix" value="$(arg namespace_prefix)" />
<arg name="eye_on_hand" value="true" />
<arg name="move_group" default="arm"/>
<arg name="tracking_base_frame" value="camera_color_optical_frame" />
<arg name="tracking_marker_frame" value="object_marker" />
<arg name="robot_base_frame" value="base_link_rm" />
<arg name="robot_effector_frame" value="ee_link" />
<arg name="freehand_robot_movement" value="true" />
<arg name="robot_velocity_scaling" value="0.1" />
<arg name="robot_acceleration_scaling" value="0.1" />
</include>
</launch>
需要修改的参数:
marker_id: 使用的marker标签的ID,选择你打印的marker标签ID;
marker_size: Marker标签的实际大小,单位为m;
/camera_info: 相机的内参话题topic,一般由启动相机的节点发布;
/image: 彩色图像话题topic;
reference_frame: marker 坐标系的参考坐标系,需要获取的是marker和相机的相对位姿,所以这里设置为相机坐标系;
camera_frame: 相机坐标系;
marker_frame: marker坐标系;
eye_on_hand: 设置为 true 时表示眼在手上,false 为眼在手外;
tracking_base_frame: marker坐标系的参考坐标系,这里是相机坐标系;
tracking_marker_frame: marker坐标系,即aruco设置的marker_frame。
标定过程
打开上一步写好的启动文件
roslaunch easy_handeye launch文件名
启动后出现包括Rviz在内的三个窗口:
打开rqt显示相机画面
rqt_image_view
如图所示
点击check starting pose确定marker相对于相机的初始位姿,依次点击Next Pose、Plan、Execute机械臂会移动到不同位置观察marker,或者手动移动机械臂到合适的位置,点击take_sample 完成一次采样。
获得足够的sample后点击compute求解,进行矩阵解算得到标定结果,translation表示机器人末端中心与相机镜头成像点的水平距离,rotation则用四元数表示x、y、z轴的旋转角度:
点击save,标定结果会被保存在~/.ros/easy_handeye/xxx.yaml中。发布base_link到camera_link的转换关系即可得到目标位置从相机坐标系到世界坐标系的转换。在机器人launch文件中发布TF静态转换示例如下:
<launch>
<!--<node pkg="tf2_ros" type="static_transform_publisher" name="base_To_cramera"
args="x y z qx qy qz qw ee_link camera_link"/> -->
<node pkg="tf2_ros" type="static_transform_publisher" name="base_To_cramera"
args="-0.06908809103480994 0.022410818173565176 0.01280247490824934
0.004867876410342842 -0.7073319749610286 -0.010143691342199057 0.7067919683350531
Link6 camera_link"/>
</launch>