UR5机械臂与realsense相机在Gazebo仿真环境下的手眼标定(眼在手上)

简介

这是一个Gazebo仿真环境下利用UR5机械臂和realsense相机进行手眼标定的教程(眼在手上)。

准备相关文件

# UR5
git clone https://github.com/UniversalRobots/Universal_Robots_ROS_Driver.git Universal_Robots_ROS_Driver
git clone -b calibration_devel https://github.com/fmauch/universal_robot.git fmauch_universal_robot
# aruco
git clone -b noetic-devel https://github.com/pal-robotics/aruco_ros.git
# vision_visp
git clone -b noetic-devel https://github.com/lagadic/vision_visp.git
# easy_hand_eye
git clone https://github.com/IFL-CAMP/easy_handeye
# realsense_ros_gazebo
git clone https://github.com/rickstaa/realsense-ros-gazebo.git

需要先创建个运行空间,然后下载好这五个文件,将realsense_ros_gazebo文件夹移动到universal_robot文件夹下
之后就是catkin_make编译下,source更新下环境。
在这里插入图片描述

修改UR5机械臂文件为其添加realsense相机

在/…/universal_robot/ur_description/urdf文件夹下找到ur5.urdf.xacro文件。对其进行修改
在此文件的开头处插入下列两行代码

 <xacro:include filename="$(find realsense_ros_gazebo)/xacro/tracker.xacro"/>
 <xacro:include filename="$(find realsense_ros_gazebo)/xacro/depthcam.xacro"/>

在此文件的后半部分插入下列代码

	<link name="support">
          <visual>
              <geometry>
                  <cylinder radius="0.02" length="0.03" />
              </geometry>
              <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
              <material name="red">
                  <color rgba="0.8 0.2 0.0 0.8" />
              </material>
          </visual>

          <collision>
              <geometry>
                  <cylinder radius="0.02" length="0.03" />
              </geometry>
              <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
          </collision>
      </link>

      <joint name="support2wrist_3_link" type="fixed">
          <parent link="${prefix}wrist_3_link" />
          <child link="support" />
          <origin xyz="0 0.05 0.06" />
      </joint>

      <gazebo reference="support">
          <material>Gazebo/White</material>
      </gazebo>
	
	<xacro:realsense_d435 sensor_name="d435" parent_link="support" rate="10">
    <origin rpy="0 0 0 " xyz="0 0 0.02"/>
    </xacro:realsense_d435>

查看相机与机械臂的结合情况

执行下列指令

#打开UR5机械臂的Gazebo仿真环境
roslaunch ur_gazebo ur5.launch 

请添加图片描述
这个可以看到相机已经固定在机械臂上端了,并且通过rqt查看可以观测到相机的视野。
这里相机观测到aruco码,这里的aruco码制作教程在我发表的其他文章里,自行查找学习制作。

创建手眼标定文件

在/home/tza/catkin_ws/src/easy_handeye/easy_handeye/launch目录下,创建手眼标定文件。
这里我创建了ur5_kinect_calibration.launch文件。

<launch>
    <arg name="namespace_prefix" default="ur5_kinect_handeyecalibration" />
    <arg name="robot_ip" doc="The IP address of the UR5 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="582"/>

    <!-- start ArUco -->
    <node name="aruco_tracker" pkg="aruco_ros" type="single">
        <remap from="/camera_info" to="/d435/color/camera_info" />
        <remap from="/image" to="/d435/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="d435_link"/>
        <param name="camera_frame"       value="d435_color_frame"/>
        <param name="marker_frame"       value="camera_marker" />
    </node>

    <!-- start the robot -->
    <include file="$(find ur_gazebo)/launch/ur5.launch">
        <arg name="limited" value="true" />
    </include>
    <include file="$(find ur5_moveit_config)/launch/ur5_moveit_planning_execution.launch">
        <arg name="limited" value="true" />
        <arg name="sim" value="true" />
    </include>
    <include file="$(find ur5_moveit_config)/launch/moveit_rviz.launch">
        <arg name="config" value="true" />
    </include>

    <!-- start easy_handeye -->
    <include file="$(find easy_handeye)/launch/calibrate.launch" >
        <arg name="namespace_prefix" value="$(arg namespace_prefix)" />
        <arg name="start_rviz" value="false" />
        <arg name="eye_on_hand" value="true" />

        <arg name="tracking_base_frame" value="d435_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.5" />
        <arg name="robot_acceleration_scaling" value="0.2" />
    </include>

</launch>

这里与easy_handeye官方提供的例子有所不同,因为不需要使用到实际的相机,所以就不需要启动实际的相机文件。
在启动UR5机械臂的时候,已经将UR5机械臂和相机一起启动了。
并且这里的机械臂启动文件也与官方提供的例子有所不同。记得注意甄别。
在启动easy_handeye这里,需要对这里进行更改,一个是关闭rviz,另外一个是进行眼在手上设置。

<arg name="start_rviz" value="false" />
<arg name="eye_on_hand" value="true" />

启动文件进行手眼标定

执行下列指令

roslaunch eye_handeye ur5_kinect_calibration.launch

程序将会打开Gazebo界面,rviz界面,和rqt_easy_handeye界面。
请添加图片描述
此时Gazebo里没有aruco码,需要自行配置插入aruco码,
之后就可以进行机械臂的标定工作了。

请添加图片描述


![请添加图片描述](https://img-blog.csdnimg.cn/be2f12b88985475db55c58c9957fb75a.png)
![请添加图片描述](https://img-blog.csdnimg.cn/fc54664160da42b9a363af81fb66359a.png)
最终经过多次标定 程序就会自动生成变换矩阵。便可以推断出相机坐标系与机械臂坐标系之间的转换关系。
  • 2
    点赞
  • 65
    收藏
    觉得还不错? 一键收藏
  • 8
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 8
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值