| UBUNTU | ROS | PYTHON | OPENCV | STATE |
|---|---|---|---|---|
By collecting multiple sets of end-effector poses from the robotic arm and camera-recognized calibration board poses as input, two types of calibration results can be obtained:
- Eye in hand: The transformation matrix between the robotic arm's end-effector and the camera.
- Eye to hand: The transformation matrix between the robotic arm's base and the camera.
$ sudo apt install libopencv-dev python3-opencv
$ sudo apt-get install ros-$ROS_DISTRO-tf-transformations
For testing, we used the Original ArUco dictionary calibration board and the piper robotic arm.
$ mkdir -p ros2_ws/src
$ cd ros2_ws/src
$ git clone
$ cd ..
$ colcon build --symlink-install
- Start the camera node according to the actual setup.
$ ros2 launch piper start_single_piper.launch.py can_port:=can0
- The robotic arm must be in teaching mode.
$ ros2 launch aruco_ros single.launch
- Need to correct the marker's size and id, as well as the image topic and frame_id.
When collecting data, it is recommended to move the robot slowly and collect more angle information.
Usage: enter collects a set of data, d deletes a set of data, q calculates the calibration result and prints it out, c exit.
$ ros2 run handeye_calibration_ros handeye_calibration --ros-args -p piper_topic:=/piper_ctrl_node/end_pose -p marker_topic:=/aruco_single/pose -p mode:=eye_in_hand
- Collection Instructions: The camera is fixed at the end of the robotic arm, and the calibration board is placed flat on the table. Operate the robotic arm to allow the camera to recognize the calibration board on the table.
$ ros2 run handeye_calibration_ros handeye_calibration --ros-args -p piper_topic:=/piper_ctrl_node/end_pose -p marker_topic:=/aruco_single/pose -p mode:=eye_to_hand
- Collection Instructions: The camera is fixed at a specific position, and the calibration board is fixed at the end of the robotic arm. Operate the robotic arm to allow the camera to recognize the calibration board at the arm's end.
| param | type | default | Description |
|---|---|---|---|
| mode | string | eye_in_hand | hand-eye calibration mode |
| min_num | int | 10 | minimum number of data sets |
| piper_topic | string | piper_ctrl_node/end_pose | robotic arm's end-effector(geometry_msgs/Pose) |
| marker_topic | string | aruco_single/pose | camera-recognized calibration board pose topic(geometry_msgs/PoseStamped) |