在手眼标定前需要安装 D435i的驱动,有一些麻烦,一步一步来
我的参考网址
关于手眼标定在参考网址中已经讲的比较清楚,我这里只是把我遇到的一些问题和大致流程罗列一下:
1,在相机标定前最好做一下检测aruco标签的测试
roslaunch realsense2_camera rs_camera.launch
roslaunch aruco_ros single.launch
rqt_image_view
看一下是否能检测到打印的TAG,注意这里需要修改这两句代码,根据tag的ID和边长尺寸,以及对应D435i发布的话题,通过rostopic list查看
<arg name="markerId" default="582"/>
<arg name="markerSize" default="0.034"/> <!-- in m -->
<remap from="/camera_info" to="/stereo/$(arg eye)/camera_info" />
<remap from="/image" to="/stereo/$(arg eye)/image_rect_color" />
我的话题修改后:
2,我在运行最后一步产生三个操作窗口的launch文件时,会出现卡死的情况所以,我将其拆分成了两部分:
ur5_realsense_handeyecalibration.launch
<?xml version="1.0"?>
<launch>
<arg name="namespace_prefix" default="ur5_D435i_handeyecalibration" />
<arg name="robot_ip" doc="The IP address of the UR5 robot" />
<!--<arg name="marker_frame" default="aruco_marker_frame"/>-->
<arg name="marker_size" doc="Size of the ArUco marker used, in meters" default="0.104" />
<arg name="marker_id" doc="The ID of the ArUco marker used" default="582" />
<!-- start ArUco -->
<node name="aruco_tracker" pkg="aruco_ros" type="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 marker_size)"/>
<param name="marker_id" value="$(arg marker_id)"/>
<!--param name="reference_frame" value="camera_color_frame"/>
<param name="camera_frame" value="camera_color_frame"/-->
<param name="reference_frame" value="camera_color_frame"/>
<param name="camera_frame" value="camera_color_frame"/>
<param name="marker_frame" value="camera_marker" />
</node>
</launch>
easy.launch
<?xml version="1.0"?>
<launch>
<!-- start easy_handeye -->
<arg name="namespace_prefix" default="ur5_D435i_handeyecalibration" />
<include file="$(find easy_handeye)/launch/calibrate.launch" >
<arg name="namespace_prefix" value="$(arg namespace_prefix)" />
<arg name="eye_on_hand" value="false" />
<arg name="tracking_base_frame" value="camera_color_frame" />
<arg name="tracking_marker_frame" value="camera_marker" />
<arg name="robot_base_frame" value="base_link" />
<arg name="robot_effector_frame" value="wrist_3_link" />
<arg name="freehand_robot_movement" value="false" />
<arg name="robot_velocity_scaling" value="0.3" />
<arg name="robot_acceleration_scaling" value="0.1" />
</include>
</launch>
3,
标定过程注意,几个特殊的流程是
3.1
注意刚开始一定要让TAG处于相机范围内,尽量靠近中间
3.2
注意一定要在第一个图中打开image_view,显示采集到的标签图像
直到窗口顶部会出现选项目录plugins->Visualization->image_View;
在打开可视化窗口后,会显示检测到的TAG有坐标系产生
3.3
大致流程是
第一步:check starting pose->Next Pose->Plan->Execute->Take Sample
第二步-第十六步:Next Pose->Plan->Execute->Take Sample
第十七步:Next Pose->Plan->Execute->Take Sample->Compute
4
眼在手上和眼在手外的代码区别主要在这一句
决定眼在手上和眼在手外,false是眼在手外
5,
注意这几个坐标的选择,经过实验,发现眼在手外的手眼标定是获得tracking_base_frame和robot_base_frame的坐标变换,而眼在手上获得的是tracking_base_frame和robot_effector_frame的坐标变换。通俗来说眼在手外获得的是相机与机械臂基座标坐标变换,而眼在手上获得的是相机与机械臂末端(工具坐标系)坐标变换。
6,
将获得的坐标变换发布到tf树中,主要是利用包自带的publish.launch文件,然后需要在文件中添加这句话,来将获取的坐标修改发布到tf树中
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args=" -0.0356404119436 -0.120097362478 -0.0206785661704 0.0111758924754 -0.0445478580565 -0.00706115101757 0.998919780521 tool0 camera_color_frame1 1000" />
总结:
代码步骤:
roslaunch ur_modern_driver ur5_bringup.launch robot_ip:=192.168.1.107
roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch
roslaunch realsense2_camera rs_camera.launch
roslaunch easy_handeye ur5_realsense_handeyecalibration.launch
roslaunch easy_handeye easy.launch
主要代码链接:
https://github.com/harrycomeon/D435i-easy_handeye