优遨机器人UR5与RealSense深度摄像头D435的手眼标定


优遨机器人UR5与RealSense深度摄像头D435的手眼标定

  • 系统环境:虚拟机VMware® Workstation 12 Pro,操作系统Ubuntu 16.04.7LTS,ROS版本Kinetic
  • 机器人型号UR5,软件版本PolyScope3.5,相机为RealSense D435

1.软件环境搭建

终端执行下面命令:

$ cd

$ mkdir -p ur_ws/src

$ cd ur_ws

$ catkin_make

然后从github仓库中clone下列软件包

$ cd src

$ git clone -b kinetic-devel https://github.com/pal-robotics/aruco_ros.git

$ git clone -b kinetic-devel https://github.com/lagadic/vision_visp.git

$ git clone https://github.com/IFL-CAMP/easy_handeye.git

$ git clone https://github.com/IntelRealSense/realsense-ros.git

$ git clone https://github.com/ros-industrial/universal_robot.git

$ git clone -b kinetic-devel https://github.com/ros-industrial/ur_modern_driver.git

安装依赖

$ rosdep install --from-paths . --rosdistro kinetic  --ignore-src

最后执行编译工作

$ cd ..

$ catkin_make

2.启动文件编辑

下面进行launch文件的编辑工作,其中的marker我们选用ArUco marker # 100的二维码标记

在easy_handeye/easy_handeye/launch目录下新建一launch文件ur5_rs_d435_hand2eye_calibration.launch,内容如下:

<launch>
    <arg name="namespace_prefix" default="ur5_camera_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.1" />
    <arg name="marker_id" doc="The ID of the ArUco marker used" default="100" />
    <!-- start the camera -->
    <include file="$(find realsense2_camera)/launch/rs_camera.launch" />
    <!--    <arg name="depth_registration" value="true" />
    </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="$(arg marker_size)"/>
        <param name="marker_id"          value="$(arg marker_id)"/>
        <param name="reference_frame"    value="camera_link"/>
        <param name="camera_frame"       value="camera_link"/>
        <param name="marker_frame"       value="camera_marker" />
    </node>
 
    <!-- start the robot -->
    <include file="$(find ur_modern_driver)/launch/ur5_bringup.launch">
        <arg name="limited" value="true" />
        <arg name="robot_ip" value="172.17.0.3" />
    </include>
    <include file="$(find ur5_moveit_config)/launch/ur5_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_link" />
        <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.2" />
        <arg name="robot_acceleration_scaling" value="0.2" />
    </include>
 
</launch>

3.手眼标定过程

终端中启动标定所需各节点,即步骤2所编辑的launch文件

$ roslaunch easy_handeye ur5_rs_d435_hand2eye_calibration.launch

然后按照下图在Rviz窗口中添加一Image并订阅话题/aruco_tracker/result,同时将运动规划的速度和加速度比例都改为0.1(仅在MotionPlanning GUI中有效)

开始时先须找到home构型,点击Check starting pose

如果出现错误提示:Can't calibrate from this position!

可以修改目录easy_handeye/easy_handeye/src/easy_handeye中的python脚本handeye_robot.py

将函数_check_target_poses(self, joint_limits)定义中的下面两行注释掉即可

            # if len(plan.joint_trajectory.points) == 0 or CalibrationMovements._is_crazy_plan(plan, joint_limits):

            #     return False

如果能找到初始构型,点击Next Pose ,然后再点击Plan,规划成功会出现绿色的矩形框提示,然后点击Execute,机器人将运动至目标构型

然后再点击take sample,得到下面的结果:

 

 这样就采样成功一次,接下来按照顺序循环执行点击Next Pose——Plan——Execute——Take Sample,直到17个采样成功结束,

若过程中出现红色的矩形提示框,为Bad Plan,即可以直接跳过当前循环执行下一次采样。

 完成所有的采样后,点击Compute,会得到标定结果,然后点击Save,结果将保存到$HOME/.ros/easy_handeye目录下的yaml文件中:

 

这样就可以得到相机坐标系和机器人坐标系之间的位姿关系了。

  • 8
    点赞
  • 44
    收藏
    觉得还不错? 一键收藏
  • 2
    评论
手眼标定是将相机与机械臂(或其他运动平台)之间的关系进行确定的过程。手眼标定的目的是确定相机坐标系与机械臂坐标系之间的变换矩阵,以实现相机与机械臂的精确配合。 下面是realsense d435i深度相机手眼标定的一般步骤: 1. 准备工作:在手眼标定之前,需要先对机械臂进行坐标系的确定,并在机械臂上安装标定板。标定板可以是一个黑白棋盘或者其他的平面,但必须能够提供足够的特征点以用于标定。同时,需要在相机上安装一个相机标定板,用于标定相机内参数。 2. 采集数据:将相机与机械臂固定在一起,通过机械臂的运动,采集多组相机与机械臂之间的位置数据。每一组数据需要记录机械臂的末端执行器位置(机械臂坐标系),以及相机拍摄到的标定板图像(相机坐标系)。 3. 提取特征点:对于每组数据,需要从相机拍摄到的标定板图像中提取出足够的特征点。常用的特征点提取算法包括SIFT、SURF等。 4. 计算变换矩阵:通过多组相机与机械臂之间的位置数据,以及相机拍摄到的标定板图像中提取出的特征点,可以计算出相机坐标系与机械臂坐标系之间的变换矩阵。 5. 验证:最后需要验证所得到的变换矩阵是否准确。可以通过将相机与机械臂移动到新的位置,然后使用标定的变换矩阵将相机坐标系转换到机械臂坐标系,验证转换后的结果是否正确。 以上是realsense d435i深度相机手眼标定的一般步骤,具体操作过程可以参考realsense官方文档。
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值