眼在外标定说明
1 环境搭建
采用的硬件设备等内容:
-
灵动Alicia D650/750单操作臂;
-
ORBBEC(奥比中光)相机;
-
Aruco 模块
Aruco 标定码
访问以下网址
点击open
打印A4 PDF, 将打印出的Aruco码裁剪到合适大小贴在硬纸板上并绑定到夹爪上。
相机准备
通过相机支架或其他工具将固定相机位置,确保相机的视野包含待识别的Aruco码。
相机需要包含RGB镜头,能够读取出RGB图像。
2 相关ROS库及依赖安装
2.1 相机ROS库
相机设备查询:
v4l2-ctl --list-devices
得到如下信息
Orbbec DaBai DCW RGB Camera: Or (usb-0000:00:14.0-1.3):
/dev/video0
/dev/video1
查询出的相机为Orbbec类型相机后,安装相应的ROS 库:
mkdir -p camera_ws/src
cd camera_ws/src
git clone https://github.com/orbbec/OrbbecSDK_ROS1?tab=readme-ov-file
cd ..
catkin_make
roscd orbbec_camera
sudo bash ./scripts/install_udev_rules.sh
echo "source ~/camera_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc
之后分别在两个终端运行以下指令启动相机:
roscore
roslaunch orbbec_camera dabai_dcw.launch
启动后新建终端输入:
rostopic list
确保以下的话题出现:
/camera/color/camera_info
/camera/color/image_raw
不同的相机话题名可能有所区别,在终端中启动
rqt_image_view
后查看不同话题的图片信息,能够显示RGB图像的话题就可用于标定,一般以color/image_raw
结尾。
2.2 标定ROS库
2.2.1 标定库安装
cd ~/camera_ws/src
git clone https://gitcode.com/gh_mirrors/ea/easy_handeye.git
cd ..
rosdep install -iyr --from-paths src
# 或者 rosdepc install -iyr --from-paths src
catkin_make
source devel/setup.bash
2.2.2 Aruco库安装
sudo apt update
sudo apt install ros-${ROS_DISTRO}-aruco-ros
3 标定代码
3.1 标定启动代码
roscd easy_handeye/launch
touch alicia_orbbec_calibration.launch
在新建的launch文件中输入以下内容:
<launch>
<arg name="namespace_prefix" default="orbbec_handeyecalibration" />
<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"/>
<!-- ============================================================== -->
<!-- == 启动机械臂的moveit控制 == -->
<!-- ============================================================== -->
<include file="$(find alicia_duo_moveit)/launch/real_robot_control.launch">
</include>
<!-- ============================================================== -->
<!-- == 启动 Orbbec Camera == -->
<!-- ============================================================== -->
<include file="$(find orbbec_camera)/launch/dabai_dcw.launch">
</include>
<!-- ============================================================== -->
<!-- == 启动 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)"/>
<!-- ArUco 结果相对于 camera_link 发布 (使用正确的相机坐标系名称) -->
<param name="reference_frame" value="camera_link"/>
<!-- 发布的标记坐标系名称 -->
<param name="marker_frame" value="camera_marker" />
</node>
<!-- ============================================================== -->
<!-- == 启动 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" /> <!-- Eye-on-Base 配置 -->
<!-- 相机基础坐标系 (TF由此发布) -->
<arg name="tracking_base_frame" value="camera_link" />
<!-- 检测到的标记坐标系 (由 ArUco 发布) -->
<arg name="tracking_marker_frame" value="camera_marker" />
<!-- 机器人基坐标系 -->
<arg name="robot_base_frame" value="base_link" />
<!-- **标记附着**在哪个连杆上 -->
<arg name="robot_effector_frame" value="tool0" />
<!-- tool0 or Link06 -->
<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>
修改高亮的代码部分,其中orbbec_handeyecalibration
标定结果文件名称,marker_size
和marker_id
改为下载的Aruco具体的大小和编号(可用直尺验证打印出的尺寸是否和理论上的尺寸匹配)
将下面的相机启动替换为实际的相机启动文件:
<include file="$(find orbbec_camera)/launch/dabai_dcw.launch">
</include>
最后,robot_effector_frame
可以是Link06
或tool0
,前者是到机械臂末端,后者是到夹爪尖端。
3.2 标定结果校验代码
touch publish_orbbec.launch
在新建的publish_orbbec.launch中输入以下内容:
<?xml version="1.0"?>
<launch>
<!-- <arg name="eye_on_hand" doc="eye-on-hand instead of eye-on-base" /> -->
<arg name="eye_on_hand" value="false" /> <!-- 确认是 Eye-on-Base -->
<arg name="verify" default="false" />
<arg name="namespace_prefix" default="easy_handeye" />
<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="base_link" />
<arg name="tracking_base_frame" default="camera_link" />
<arg name="inverse" default="false" />
<arg name="calibration_file" default="" />
<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"/>
<!-- ============================================================== -->
<!-- == 启动 orbbec camera == -->
<!-- ============================================================== -->
<include file="$(find orbbec_camera)/launch/dabai_dcw.launch">
</include>
<!--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>
<node pkg="tf" type="static_transform_publisher" name="camera_link_to_optical_frame_broadcaster"
args="0.0 0.0 0.0 -1.570796 0 -1.570796 camera_link camera_color_optical_frame 100" />
<!-- 这个通常是固定的旋转,RPY=(0, -pi/2, -pi/2) 是常见约定 -->
<!-- Conditionally launch ArUco tracker for Realsense -->
<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)"/>
<!-- ArUco 结果相对于 camera_link 发布 (使用正确的相机坐标系名称) -->
<param name="reference_frame" value="camera_link"/>
<param name="camera_frame" value="camera_color_optical_frame"/>
<!-- 发布的标记坐标系名称 -->
<param name="marker_frame" value="camera_marker" />
</node>
</launch>
安装3.1节中同样的修改方式修改上述高亮的代码行。
3.3 现有代码修改
打开同路径下的calibrate.launch
, 修改下面的参数调整标定时机械臂的运动幅度,这些参数可自行设置,没有标准值。
<arg name="translation_delta_meters" default="0.05" doc="the maximum movement that the robot should perform in the translation phase" />
<arg name="rotation_delta_degrees" default="10" doc="the maximum rotation that the robot should perform" />
<arg name="robot_velocity_scaling" default="0.3" doc="the maximum speed the robot should reach, as a factor of the speed declared in the joint_limits.yaml" />
<arg name="robot_acceleration_scaling" default="0.2" doc="the maximum acceleration the robot should reach, as a factor of the acceleration declared in the joint_limits.yaml" />
修改~/alicia_ws/src/alicia_duo_moveit/launch/real_robot_control.launch
:
<include file="$(find easy_handeye)/launch/publish_orbbec.launch" if="$(arg camera_load)">
<arg name="namespace_prefix" value="orbbec_handeyecalibration"/>
</include>
修改orbbec_handeyecalibration
为alicia_orbbec_calibration.launch
中的标定结果名称,文件的具体路径为~/.ros/easy_handeye/orbbec_handeyecalibration_eye_on_base.yaml
(需要完成标定才有该文件)
4 眼在外相机外参标定
4.1 运行标定代码
在2个终端中分别运行:
roslaunch alicia_duo_driver serial_server.launch
roslaunch easy_handeye alicia_orbbec_calibration.launch
在另一个终端中输入:
rqt_image_view
话题切换为:
/aruco_tracker/result
确保在rqt_image_view
中能看到识别中的Aruco坐标:
且弹出4个窗口,分别是:
用于机械臂标定位置移动。
用于标定的数据采集。
和两个Rviz界面,可观测到标定过程中Aruco码的移动过程。
如出现以下错误,可忽略或将
Gloable Options
下的Fixed Frame
改为base_link
4.2 外参标定具体步骤
- 检查标定的起始位姿是否可以标定
- 规划机械臂位置
若出现以下界面,可用MoveIt调整机械臂的起始位姿重新检测
- 执行规划步骤
- 标定数据采集
重复步骤2-4直到17个位姿的标定数据采集完。
- 标定结果计算
保存后可在~/.ros/easy_handeye/
路径下找到标定结果文件。