typora-root-url |
---|
./ |
Automatic hand-eye calibration of the UR5 robotic arm based on the open-source project easy_handeye and ROS. The calibration involves the static Kinect v2 camera installed on the surrounding (eye on base) and the RealSense D435 camera mounted on the ur5 end link (eye on hand).
-
(Tested) Ubuntu18.04 ros-melodic
-
UR5 robotic arm, PolyScope firmware3.9 (tested)
-
Follow official instruction to install Universal_Robots_ROS_Driver and fmauch_universal_robot packages.
-
Create a
controllers.yaml
file in pathuniversal_robot/ur5_moveit_config/config
and write the following: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
-
Please check whether the
externalcontrol-1.0.5.urcap
has been installed on the control panel of your UR5, if not, follow the official instruction, configure your UR5 and installexternalcontrol-1.0.5.urcap
and setting your workstation IP. -
Extracting robot calibration parameters. These parameters are not obtained from hand-eye calibration and are perceived as a means to characterize and compensate for errors arising from the robotic arm's installation and wear. It is important to distinguish between the two.
roslaunch ur_calibration calibration_correction.launch \ robot_ip:=<your_robot_ip> target_filename:="${HOME}/my_robot_calibration.yaml"
-
Clone and install.
cd ~/catkin_ws/src git clone https://github.com/Hymwgk/ur5_hand_eye_calibrate.git cd .. catkin_make source ~/catkin_ws/devel/setup.bash
-
After completing all dependency installations and configurations, make sure your
catkin_ws/src
folder has the following structure.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
-
Install the camera and calibration board as shown bellow. The calibration board utilizes a 10cm x 10cm QR code label generated by ar_track_alvar, with an ID of 7. Ensure that the camera can observe the complete label.
-
Start the low-level controller, change the IP address to the fixed IP of your UR5 robotic arm, and set the path for the robotic arm calibration parameters to the previously saved path.
roslaunch ur_robot_driver ur5_bringup.launch robot_ip:=<your_robot_ip> \ kinematics_config:="${HOME}/my_robot_calibration.yaml"
-
On the UR5 control panel, launch the program interfaced with ROS. Refer to this link for instructions. Please note that this operation must be performed after step 2.
-
Start the top-level MoveIt-related ros nodes.
roslaunch ur5_hand_eye_calibrate ur5_moveit_rviz.launch
-
Start the camera and publish related transformations.
roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true
-
Start monitor to prevent collisions between the robotic arm and the surrounding environment.
rosrun kinect2_viewer kinect2_viewer kinect2 sd cloud
-
Start the hand-eye calibration, please follow the on-screen operation instructions.
roslaunch ur5_hand_eye_calibrate ur5_eob.launch
Here we perform calibration for the RealSense D435 depth camera installed on the robotic arm.
-
Place the calibration board, identical to the one used for the
eye on base
calibration, on the desktop, ensuring that the calibration board is within the camera's field of view. -
Start the low-level controller, change the IP address to the fixed IP of your UR5 robotic arm, and set the path for the robotic arm calibration parameters to the previously saved path.
roslaunch ur_robot_driver ur5_bringup.launch robot_ip:=192.168.1.110 \ kinematics_config:="${HOME}/my_robot_calibration.yaml"
-
On the UR5 control panel, launch the program interfaced with ROS ,following the same steps as for the "eye on base."
-
Start the top-level MoveIt-related ros nodes.
roslaunch ur5_hand_eye_calibrate ur5_moveit_rviz.launch
-
Start the camera and publish related transformations.
roslaunch realsense2_camera rs_camera.launch
-
Start the calibration, please follow the on-screen operation instructions.
roslaunch ur5_hand_eye_calibrate ur5_eoh.launch
-
Publish the hand-eye pose transformation (eye on base).
roslaunch ur5_hand_eye_calibrate publish_ur5_eob.launch
-
Or publish the hand-eye pose transformation (eye on hand).
roslaunch ur5_hand_eye_calibrate publish_ur5_eoh.launch
-
Unlock the UR5 robotic arm and start MoveIt&Rviz.
roslaunch ur_robot_driver ur5_bringup.launch robot_ip:=192.168.1.110 kinematics_config:="${HOME}/my_robot_calibration.yaml" # In another shell. roslaunch ur5_hand_eye_calibrate ur5_moveit_rviz.launch
If there are issues with tf, try restart the MoveIt steps.