realman机械臂手眼标定

环境要求

  • 系统:Ubuntu 18.04.6
  • ROS:melodic
  • OpenCV 库:OpenCV 3.2.0
  • Realsense D435:librealsense sdk(2.50.0)、realsense-ros 功能包(2.3.2)
  • Marker 标记识别:Aruco 功能包
  • 手眼标定:easy_handeye 功能包
  • Moveit!
  • RM 机械臂 ROS 功能包(根据不同型号机械臂提供配套的 ROS 包,使用方法基本相同,提供有配套的使用说明文档,这里以 RM75-B 机械臂配套的 ROS 包即 rm_75_robot 为例)
  • Catkin-tools 工具包

准备工作

将相机安装固定到机械臂末端

将相机通过转接件固定到机械臂末端,如图所示(这里未安装末端工具,用户如需要可
以一并装上):

在这里插入图片描述

给机械臂接线

  • 机械臂接上电源
  • 机械臂外侧网口通过网线连接到主机或交换机上(注意:机械臂默认固定 IP 为192.168.1.18,所以要确保主机与机械臂在同一局域网内能够连通)
  • 相机通过 Type-C 数据线将相机与主机 USB3.0 接口相连

测试IP

主机与机械臂都上电启动后,在主机打开终端,执行以下命令测试主机与机械臂是否连通:

ping 192.168.1.18

在这里插入图片描述

打印 Marker 标签

打印标定需要使用到的 Marker 标签,可以在 aruco_ros 包中找到提供好的 marker 标签进行打印,如图:
在这里插入图片描述
也可以从下面的网站下载 marker 标签并打印出来:
https://chev.me/arucogen/

在这里插入图片描述

  • Dictionary 一定要选 Original ArUco
  • Marker ID 和 Marker size 自选,在 launch 文件中做相应的修改(本教程演示使用 MarkerID:582,Marker size:50mm)
  • 打印时,要选择原始大小,否则要测量一下打印出来的真实大小。

aruco_ros 配置

简介

aruco 是一种类似二维码的定位标记辅助工具,通过在环境中部署 Markers,可以辅助机器人进行定位,弥补单一传感器的缺陷,纠正误差,本教程使用的手眼标定 easy_handeye 功能包需要借助这个工具进行手眼标定。

配置 aruco_ros 的 launch 文件

在 aruco_ros 功能包的 launch 目录下拷贝一份原有的 single.launch 文件或新建一个 launch文件,命名为 single_realsense.launch,执行以下命令(本教程默认用户 ROS 的工作空间为cakin_ws,用户根据实际的环境进入相应路径进行操作):

cd ~/catkin_ws/src/aruco_ros/aruco_ros/launch
touch single_realsense.launch
gedit single_realsense.launch

根据以下内容进行修改或者覆盖为以下内容后保存:

<launch>
<arg name="markerId" default="582"/>
<arg name="markerSize" default="0.05"/> <!-- in m -->
<arg name="eye" default="left"/>
<arg name="marker_frame" default="aruco_marker_frame"/>
<arg name="ref_frame" default="camera_color_frame"/> <!-- leave empty and the pose will be
published wrt param parent_name -->
<arg name="corner_refinement" default="LINES" /> <!-- NONE, HARRIS, LINES, SUBPIX -->
<node pkg="aruco_ros" type="single" name="aruco_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 markerSize)"/>
<param name="marker_id" value="$(arg markerId)"/>
<param name="reference_frame" value="$(arg ref_frame)"/> <!-- frame in which the marker
pose will be refered -->
<param name="camera_frame" value="camera_color_frame"/>
<param name="marker_frame" value="$(arg marker_frame)" />
<param name="corner_refinement" value="$(arg corner_refinement)" />
</node>
</launch>

在这里插入图片描述

  • markerId:使用的 Marker 标签的 ID,这里在准备时打印的 Marker 标签 ID 为 582
  • markerSize:Marker 标签的实际大小,单位为 m,这里在准备时打印的 Marker 标签实际大小为 5 厘米即 0.05m
  • ref_frame:参考坐标系名称,这里选择 Realsense 的 camera_color_frame 作为参考坐标系
  • :将/camera_info 重映射为对应 Realsense实际发布的相应的 Topic 即/camera/color/camera_info
  • :将/image 重映射为对应 Realsense 实际发布的相应的 Topic 即/camera/color/image_raw
  • camera_frame:相机坐标系,修改为实际的相机坐标系 camera_color_frame

easy_handeye 配置

简介

easy_handeye 是用于手眼标定的功能包之一,借助它可以实现眼在手上和眼在手外的手眼标定,在这里我们介绍使用 easy_handeye 完成眼在手上的手眼标定。

配置 easy_handeye 标定的 launch 文件

在 easy_handeye 功能包的 launch 目录下新建一个 launch 文件,命名为
eye_in_hand_calibrate.launch,执行以下命令(本教程默认用户 ROS 的工作空间为 cakin_ws,用户根据实际的环境进入相应路径进行操作):

cd ~/catkin_ws/src/easy_handeye/easy_handeye/launch
touch eye_in_hand_calibrate.launch
gedit eye_in_hand_calibrate.launch

编辑输入以下内容并保存:

<?xml version="1.0" ?>
<launch>
	<!-- 生成标定文件的名称 -->
	<arg name="namespace_prefix" default="rm_rs_d435" />
	<!-- RM 机械臂 MoveIt!配置的 move_group 为 arm,所以修改为 arm -->
	<arg name="move_group" default="arm" />
	<!-- start easy_handeye -->
	<include file="$(find easy_handeye)/launch/calibrate.launch" >
		<arg name="namespace_prefix" value="$(arg namespace_prefix)" />
		<arg name="move_group" value="$(arg move_group)" />
		<!-- 这里使用眼在手上的方式进行标定,所以此处改成 true -->
		<arg name="eye_on_hand" value="true" />
		<!--tracking_base_frame 为 realsense 的相机坐标系-->
		<arg name="tracking_base_frame" value="camera_color_frame" />
		<!--tracking_marker_frame 对应 aruco_ros 包中 single_realsense.launch 中的 marker_frame 的值-->
		<arg name="tracking_marker_frame" value="aruco_marker_frame" />
		<!--robot_base_frame 为机器人基座坐标系-->
		<arg name="robot_base_frame" value="base_link" />
		<!--robot_effector_frame 为工具坐标系,如夹爪,吸盘等,但实际的 rm 机器人模型未添加夹爪,
		所以这里设置为末端关节 Link7-->
		<arg name="robot_effector_frame" value="Link7" />
		<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>

注意:这里是以 RM75 即 7 轴机械臂为例所以为 Link7,如果使用的是 RM65 即 6 轴机械臂,则应该修改为 Link6

配置发布 TF 的 launch 文件

手眼标定完成后需要根据标定的文件发布 TF 坐标转换才能够将相机识别到物体的坐标转换到相应机械臂的坐标系上,修改 easy_handeye 功能包的 launch 目录下的 publish.launch文件,执行以下命令(本教程默认用户 ROS 的工作空间为 cakin_ws,用户根据实际的环境进入相应路径进行操作):

cd ~/catkin_ws/src/easy_handeye/easy_handeye/launch
gedit publish.launch

编辑修改对应的内容并保存:

<?xml version="1.0"?>
<launch>
	<!--修改 eye_on_hand 参数默认为 true -->
	<arg name="eye_on_hand" doc="eye-on-hand instead of eye-on-base" default="true" />
	<!--修改 namespace_prefix 参数,与眼在手上标定 launch 文件[eye_in_hand_calibrate.launch]中的
	“namespace_prefix”一致,这样才能找到标定好的 YAML 文件-->
	<arg name="namespace_prefix" default="rm_rs_d435" />
	<arg if="$(arg eye_on_hand)" name="namespace" value="$(arg namespace_prefix)_eye_on_hand" />
	<arg unless="$(arg eye_on_hand)" name="namespace" value="$(arg namespace_prefix)_eye_on_base" />
	<!--it is possible to override the link names saved in the yaml file in case of name clashes, for example-->
	<arg if="$(arg eye_on_hand)" name="robot_effector_frame" default="" />
	<arg unless="$(arg eye_on_hand)" name="robot_base_frame" default="" />
	<arg name="tracking_base_frame" default="" />
	<arg name="inverse" default="false" />
	<arg name="calibration_file" default="" />
	<!--publish hand-eye calibration-->
	<group ns="$(arg namespace)">
		<param name="eye_on_hand" value="$(arg eye_on_hand)" />
		<param unless="$(arg eye_on_hand)" name="robot_base_frame" value="$(arg robot_base_frame)" />
		<param if="$(arg eye_on_hand)" name="robot_effector_frame" value="$(arg robot_effector_frame)" />
		<param name="tracking_base_frame" value="$(arg tracking_base_frame)" />
		<param name="inverse" value="$(arg inverse)" />
		<param name="calibration_file" value="$(arg calibration_file)" />
		<node name="$(anon handeye_publisher)" pkg="easy_handeye" type="publish.py" output="screen"/>
	</group>
</launch>

在这里插入图片描述

启动相关 launch 文件开始标定

启动 Realsense 节点

首先确认相关 ROS 包都已编译,执行如下命令确保能够编译成功:

cd ~/catkin_ws
catkin build

在这里插入图片描述
确认相机通过 Type-C 数据线将相机与主机 USB3.0 接口相连,执行如下命令启动Realsense 节点:

cd ~/catkin_ws
source devel/setup.bash
roslaunch realsense2_camera rs_camera.launch

在这里插入图片描述

启动 aruco 节点识别 Marker 标签

打开一个新的终端,执行以下命令启动 single_realsense.launch

cd ~/catkin_ws
source devel/setup.bash
roslaunch aruco_ros single_realsense.launch

在这里插入图片描述

启动 image_view 节点显示图像

打开一个新的终端,执行以下命令启动 image_view 订阅/aruco_single/result 显示图像:

cd ~/catkin_ws
source devel/setup.bash
rosrun image_view image_view image:=/aruco_single/result

在这里插入图片描述

启动 RM 机械臂的 control 和 driver 节点

打开一个新的终端,执行以下命令启动 control 节点:

cd ~/catkin_ws
source devel/setup.bash
roslaunch rm_75_control rm_75_control.launch

注意:本教程以 RM75 机械臂为例,如果使用的是 6 轴即 RM65 机械臂,则启动 control的命令为:roslaunch rm_control rm_control.launch

在这里插入图片描述
再打开一个新的终端,执行以下命令启动 driver 节点:

cd ~/catkin_ws
source devel/setup.bash
roslaunch rm_75_bringup rm_robot.launch

注意:本教程以 RM75 机械臂为例,如果使用的是 6 轴即 RM65 机械臂,则启动 driver的命令为:roslaunch rm_bringup rm_robot.launch
运行成功后在 rviz 中可以看到机器人模型与真实机械臂的状态保持一致,如图所示:
在这里插入图片描述
在 rviz 的 MotionPlanning 下的 Planning,Goal State 选择 forward 然后点击 Plan & Execute,可以看到真实机械臂会按照 rviz 中 MoveIt!规划的路径运动,如图所示:
在这里插入图片描述

启动 easy_handeye 手眼标定节点

在启动标定程序前,建议先在 rviz 中通过 Moveit 或手动调节机械臂到一个合适的姿态,然后将 aruco 二维码移动至相机视野中心处附近,如图所示(建议参考图中的姿态,避免在标定时有不可达的规划):

在这里插入图片描述
打开一个新的终端,执行以下命令启动手眼标定节点:

cd ~/catkin_ws
source devel/setup.bash
roslaunch easy_handeye eye_in_hand_calibrate.launch

成功运行后,会同时打开三个界面:
在这里插入图片描述
在这里插入图片描述
在这里插入图片描述

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

点PY

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值