This repository contains the 6-DoF Grasp Planning for the Automated Item Picking (AIP) application at the University of Applied Sciences in Karlsruhe (HKA).
The grasp planning is based on the following operations:
-
Preprocessing
- Receive depth image from the Roboception camera
- Transform the depth image based on the object mask from ODTF into a point cloud with a resolution of 10mm
-
Determination of the 6-DoF grasp poses
- Filtering the point cloud
- Extraction of the object surface with RANSAC algorithm including projection of all points onto the determined surface
- Determination of the normal vector for the surface
- Determination of the grasp point as median of all relevant points in the point cloud
- Determination of the grasp vector by including the orientation per package received from ODTF
-
Bosch vaccuum gripper (with 4 pneumatic individually actuated cylinders)
- Dynamic gripper selection based on the detected package
- Offset calculation to provide the correct grasp poses
To calculate the inverse kinematics of the robot, the Trac-IK solver is configured and used in aip_bringup.
The path planning and trajectory planning remains on the commonly used one's in MoveIt.
Build and start the Docker aip_grasp_planning:
source build_docker.sh
source start_docker.sh
Launch the nodes for grasp planning:
ros2 launch aip_grasp_planning grasp_planning.launch.py
Inputs | Outputs |
---|---|
- Objects to Pick and Place - Package Sequence for placement planning - Depth image - Detections from ODTF |
- Pick poses - Cylinder IDs to grasp the objects - Place poses |
The necessary interfaces from ODTF and Packing Planning are cloned from the most recent GitHub status of the main repositories per module (see Dockerfile). Consequently, they are only visible after attaching to the running container. If you need to adapt the interfaces, please change them in the repository of the modules and rebuild the docker image.
For more information on the necessary inputs and outputs, please review the module repositories:
Grasp poses and the resulting object surface point cloud can be visualized in RVIZ. Therefore the following topics are published:
- /grasp_object_surface_point_cloud (White PointCloud2)
- /grasp_poses (Green arrow)
- /grasp_poses_with_offset (Red arrow)
Launch the point transformation node for additional debugging:
ros2 launch point_transformation point_transformation.launch.py