内参数
1.ur3_realsense_calibration.launch
<launch>
<arg name="namespace_prefix" default="ur3_realsense_handeyecalibration" />
<arg name="robot_ip" doc="The IP address of the UR3 robot" />
<arg name="marker_size" doc="Size of the ArUco marker used, in meters" default="0.1" />
<arg name="marker_id" doc="The ID of the ArUco marker used" default="100" />
<!-- start the realsense -->
<include file="$(find realsense2_camera)/launch/rs_camera.launch" >
</include>
<!-- 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="0.1"/>
<param name="marker_id" value="100"/>
<param name="reference_frame" value="camera_color_frame"/>
<param name="camera_frame" value="camera_color_frame"/>
<param name="marker_frame" value="camera_marker" />
</node>
<!-- start the robot -->
<include file="$(find ur_modern_driver)/launch/ur3_bringup.launch">
<arg name="limited" value="true" />
<arg name="robot_ip" value="192.168.31.64" />
</include>
<include file="$(find ur3_moveit_config)/launch/ur3_moveit_planning_execution.launch">
<arg name="limited" value="true" />
</include>
<!-- 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="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="tool0_controller " />
<arg name="freehand_robot_movement" value="false" />
<arg name="robot_velocity_scaling" value="0.5" />
<arg name="robot_acceleration_scaling" value="0.2" />
</include>
</launch>
2.启动标定程序:roslaunch ur3_realsense_calibration.launch
3.将标定的结果实时显示出来:
方式1:查看home隐藏文件夹.ros/easy_handeye下标定结果文件yaml。将变换矩阵按照以下格式写 static_transform_publisher.launch文件改写一个实时(100hz)发布位置转换关系的launch文件,放在easy_handeye/easy_handeye/launch(和之前的ur3_realsense_calibration.launch在一个包里),这里的args 分别对应x y z qx qy qz qw frame_id child_frame_id period_in_ms。
启动static_transform_publisher.launch文件
roslaunch static_transform_publisher.launch
<launch>
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="0.7810954111863362 0.4362160638790268 0.16301827937001387 -0.20452635132067903 -0.7688849381709477 0.5396310162123635 0.275287649216088 base_link camera_link 100" />
</launch>
方式2:利用easy_handeye文件夹下面的publish.launch文件。将static_transform_publisher添加在该launch文件的末尾处,如下:
</group>
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args=" 0.7810954111863362 0.4362160638790268 0.16301827937001387 -0.20452635132067903 -0.7688849381709477 0.5396310162123635 0.275287649216088 base_link camera_link 100" />
启动 roslaunch easy_handeye publish.launch eye_on_hand:=false namespace_prefix:=ur3_realsense_handeyecalibration即可将获得的手眼标定结果成功的发布出去。
4.标定完成后temerial末尾会得到从相机转世界的刚体变换矩阵