Geometry based graspable target detection for legged robots.
Originated in the Space Robotics Lab (SRL) of the Tohoku University. Based on ClimbLab (Uno et al. 2022).
-
Jitao Zheng ([email protected])
-
Taku Okawara ([email protected])
-
Kentaro Uno ([email protected])
-
Antonin Ringeval-Meusnier ([email protected])
The code was tested on:
- ROS Humble
- Ubuntu 22.04
- gcc version 11.4.0
You will require the following packages and libraries:
- Point Cloud Library (PCL)
- LibInterpolate
- Eigen3
-
Installation of Catch2
git clone https://github.com/catchorg/Catch2.git cd Catch2 cmake -B build -S . -DBUILD_TESTING=OFF sudo cmake --build build/ --target install
-
Installation of LibInterpolate
git clone https://github.com/CD3/libInterpolate cd libInterpolate mkdir build cd build cmake .. make sudo make install
-
Make Sure that you have ALL the pcl libraries installed
If you don't have yet installed Point Cloud Library (PCL), you can install it by typing:
sudo apt install libpcl-dev sudo apt install ros-humble-pcl-ros
Open a new terminal window.
Type:
cd ~/ros2_ws/src
Clone the repository:
git clone [email protected]:Space-Robotics-Laboratory/graspable_points_detection_ros2.git
Then we can build it:
cd ..
colcon build
IMPORTANT, don't forget to sourcing the packages you just build in order for them to show when you want to run them:
source install/setup.bash
We will first test the algorithm on some examples. You will need at least three terminals.
-
Terminal 1
Launch the graspable target detection.
cd ~/ros2_ws source install/setup.bash ros2 run detect_graspable_points detect_graspable_points_main
The algorithm subscribes to a point cloud message
merged_pcd
insensor_msgs/PointCloud2
format. So in principle, you can subscribe to any tope -
Terminal 2
Publish stored example point cloud.
cd ~/ros2_ws source install/setup.bash ros2 run detect_graspable_points publish_pointcloud2
Now, a point cloud in .pcd format will be published once per second as
sensor_msgs/PointCloud2
message under the topic/merged_pcd
in theregression_plane_frame
coordinate frame. -
Terminal 3
Open RViz.
cd ros2 run rviz2 rviz2
You can freely choose which topic you want to visualize, whether that is the raw point cloud with the graspable points (light green spheres) or the color gradient of Graspability Score.
Copy the point cloud you want to examine into the folder detect_graspable_points/src/pcd_data/
and change the path in the program publish_pointcloud2.cpp
. Make sure that it is in .pcd format. Of course the algorithm can also subscribe to any PointCloud2 message with the name /merged_pcd
coming from other nodes.
This package output several data for visualization. If you are only interested in the graspable point it is pulished as /detect_graspable_point/graspable_points
. To choose the different gripper in this file just turn to true the gripper you want to use and flase the others.
The edition of parameters now takes place in settings.hpp
in include/detect_graspbable_points
folder.
Orientate yourself to the simplified dimensions of this gripper:
No. | Variable | Explanation |
---|---|---|
1 | Palm diameter | Diameter of gripper's palm |
2 | Palm diameter of finger joints | Distance between two opposite first finger joints |
3 | Finger length | Length of the first finger segment |
4 | Spine length | Length of the last finger segment |
5 | Spine depth | Length of the spine itself |
6 | Opening angle | Maximum opening angle |
7 | Closing angle | Maximum closing angle |
8 | Opening spine radius | Distance from the center of the palm to the tip of the furthest spine |
9 | Opening spine depth | Distance from the horizontal plane to the tip of the spine when opened |
10 | Closing height | Vertical distance between the tip of the spine and the bottom of the palm when closed |
TODO: I don't know what exactly "margin_of_top_solid_diameter" and "inside_margin_of_bottom_void_diameter" are. Please complement this Readme if anyome knows more.
The matching parameters are the most essential parameters for the graspability and curvature analysis.
No. | Variable | Data type | Explanation |
---|---|---|---|
1 | Voxel size | float [m] | Size of voxels you want to use |
2 | Threshold of Solid Voxels | int | Number of solid voxels needed to not apply penalty coefficient |
3 | Artificial_add_point | String (on/off) | True if you think your map is too sparse for running properly |
4 | Delete lower targets z-threshold | float [m] | Threshold below which point are not checked for graspability |
5 | Auxiliary void voxel layers above gripper mask | int | Empty layers to avoid false matching on too convex shape |
6 | Graspability threshold | int | Graspability above which we consider graspable with certainty |
- If libinterpolated dosn't get build even after installing catch2, make sure to have GSL installed and restarting your computer might help.