typora-root-url |
---|
./ |
基于easy_handeye开源项目,对ur5机械臂进行手眼标定(Kinect v2眼在手外,realsenseD435 眼在手上);里面主要是修改了一些easy_handeye中的一些launch文件,实现手眼转换矩阵的计算与发布。
-
Ubuntu18.04 ros-melodic
-
ur5机械臂,PolyScope固件版本3.9
-
参照官方教程安装Universal_Robots_ROS_Driver 与 fmauch_universal_robot包
-
在
universal_robot/ur5_moveit_config/config
中创建controllers.yaml
文件,并写入controller_list: - name: "" action_ns: /scaled_pos_traj_controller/follow_joint_trajectory type: FollowJointTrajectory joints: - shoulder_pan_joint - shoulder_lift_joint - elbow_joint - wrist_1_joint - wrist_2_joint - wrist_3_joint
-
按照官方教程,对ur5机械臂端进行配置,主要是在ur5端安装
externalcontrol-1.0.5.urcap
,并设置工作站ip -
抽取机械臂校准参数,该参数并非手眼标定得到的参数,个人感觉是为了描述和弥补机械臂自身安装、磨损等造成的误差,注意区分
roslaunch ur_calibration calibration_correction.launch \ robot_ip:=192.168.1.110 target_filename:="${HOME}/my_robot_calibration.yaml"
-
安装本项目文件
cd ~/catkin_ws/src git clone https://github.com/Hymwgk/ur5_hand_eye_calibrate.git cd .. catkin_make source ~/catkin_ws/devel/setup.bash
-
完成包括依赖在内的所有安装后,确保src文件夹中存在如下结构:
wgk@wgk:~/catkin_ws/src$ tree -L 1 . ├── CMakeLists.txt -> /opt/ros/melodic/share/catkin/cmake/toplevel.cmake ├── easy_handeye ├── fmauch_universal_robot ├── iai_kinect2 ├── Universal_Robots_ROS_Driver └── ur5_hand_eye_calibrate 5 directories, 1 file
-
自行安装好相机和标定板,标定板使用 ar_track_alvar生成的10cm*10cm的二维码标签,id为7,确保相机能够观察到完整标签
-
单独启动底层controller,将ip地址更换为你的ur5机械臂固定ip,机械臂校准参数路径也设置为之前保存的路径
roslaunch ur_robot_driver ur5_bringup.launch robot_ip:=192.168.1.110 \ kinematics_config:="${HOME}/my_robot_calibration.yaml"
-
在ur5控制板上,启动与ros对接的程序,方法参见此处,注意,该操作必须在步骤2之后执行
-
启动顶层moveit相关节点
roslaunch ur5_hand_eye_calibrate ur5_moveit_rviz.launch
-
另一个命令窗口,打开相机,并进行监视,防止机械臂与与周边环境发生碰撞
roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true rosrun kinect2_viewer kinect2_viewer kinect2 sd cloud
-
打开窗口进行监视
rosrun kinect2_viewer kinect2_viewer kinect2 sd cloud
-
另一个命令窗口,进行标定,按照提示进行标定
roslaunch ur5_hand_eye_calibrate ur5_eob.launch
使用realsense d435深度相机,安装在机械手上;
-
将标签放置在桌面上,标定板与eye on base相同,确保相机视野范围能够看到标签
-
单独启动底层controller,将ip地址更换为你的ur5机械臂固定ip,机械臂校准参数路径也设置为之前保存的路径
roslaunch ur_robot_driver ur5_bringup.launch robot_ip:=192.168.1.110 \ kinematics_config:="${HOME}/my_robot_calibration.yaml"
-
在ur5控制板上,启动与ros对接的程序,与eye on base相应步骤相同
-
启动顶层moveit相关节点
roslaunch ur5_hand_eye_calibrate ur5_moveit_rviz.launch
-
另一个命令窗口,打开相机
roslaunch realsense2_camera rs_camera.launch
-
另一个命令窗口,进行标定,按照提示进行标定
roslaunch ur5_hand_eye_calibrate ur5_eoh.launch
-
eye on base发布手眼姿态矩阵
roslaunch ur5_hand_eye_calibrate publish_ur5_eob.launch
-
或者eye on hand发布手眼姿态矩阵
roslaunch ur5_hand_eye_calibrate publish_ur5_eoh.launch
-
解锁ur5机械臂,并启动Moveit
roslaunch ur_robot_driver ur5_bringup.launch robot_ip:=192.168.1.110 kinematics_config:="${HOME}/my_robot_calibration.yaml" #另一窗口 roslaunch ur5_hand_eye_calibrate ur5_moveit_rviz.launch
如果tf出现问题,就先重新启动Moveit步骤