diff --git a/.readthedocs.yml b/.readthedocs.yml
index eed82cc..9ab6142 100644
--- a/.readthedocs.yml
+++ b/.readthedocs.yml
@@ -12,7 +12,8 @@ sphinx:
# Build documentation with MkDocs
#mkdocs:
# configuration: mkdocs.yml
-
+build:
+ image: stable
# Optionally build your docs in additional formats such as PDF
formats:
- pdf
diff --git a/LICENSE b/LICENSE
new file mode 100644
index 0000000..dd43581
--- /dev/null
+++ b/LICENSE
@@ -0,0 +1,21 @@
+MIT License
+
+Copyright (c) 2025 GraspNet
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
diff --git a/README.md b/README.md
index 6a84cb1..1713992 100644
--- a/README.md
+++ b/README.md
@@ -1,11 +1,12 @@
# graspnetAPI
+[](https://badge.fury.io/py/graspnetAPI)
## Dataset
Visit the [GraspNet Website](http://graspnet.net) to get the dataset.
## Install
-You can install using pip.
+You can install using pip. (Note: The pip version might be old, install from the source is recommended.)
```bash
pip install graspnetAPI
```
@@ -32,6 +33,12 @@ bash build_doc.sh
LaTeX is required to build the pdf, but html can be built anyway.
+## Grasp Definition
+The frame of our gripper is defined as
+
+

+
+
## Examples
```bash
@@ -56,6 +63,14 @@ Please refer to our document for more examples.
## Citation
Please cite these papers in your publications if it helps your research:
```
+@article{fang2023robust,
+ title={Robust grasping across diverse sensor qualities: The GraspNet-1Billion dataset},
+ author={Fang, Hao-Shu and Gou, Minghao and Wang, Chenxi and Lu, Cewu},
+ journal={The International Journal of Robotics Research},
+ year={2023},
+ publisher={SAGE Publications Sage UK: London, England}
+}
+
@inproceedings{fang2020graspnet,
title={GraspNet-1Billion: A Large-Scale Benchmark for General Object Grasping},
author={Fang, Hao-Shu and Wang, Chenxi and Gou, Minghao and Lu, Cewu},
@@ -64,3 +79,17 @@ Please cite these papers in your publications if it helps your research:
year={2020}
}
```
+
+## Change Log
+
+#### 1.2.6
+
+- Add transformation for Grasp and GraspGroup.
+
+#### 1.2.7
+
+- Add inpainting for depth image.
+
+#### 1.2.8
+
+- Minor fix bug on loadScenePointCloud.
diff --git a/docs/build_doc.sh b/docs/build_doc.sh
index 84937aa..ebe6ad8 100755
--- a/docs/build_doc.sh
+++ b/docs/build_doc.sh
@@ -1,6 +1,3 @@
-cd ..
-bash install.sh
-cd docs
rm source/graspnetAPI.*
rm source/modules.rst
sphinx-apidoc -o ./source ../graspnetAPI
diff --git a/docs/requirements.txt b/docs/requirements.txt
index a8ce1e8..9978f9a 100644
--- a/docs/requirements.txt
+++ b/docs/requirements.txt
@@ -1,2 +1,3 @@
sphinx==3.0.3
-sphinx_rtd_theme
\ No newline at end of file
+sphinx_rtd_theme
+open3d==0.11.0
diff --git a/docs/source/_static/grasp_definition.png b/docs/source/_static/grasp_definition.png
new file mode 100644
index 0000000..bd6e4f5
Binary files /dev/null and b/docs/source/_static/grasp_definition.png differ
diff --git a/docs/source/_static/rect_grasp_definition.png b/docs/source/_static/rect_grasp_definition.png
new file mode 100644
index 0000000..c14d7bc
Binary files /dev/null and b/docs/source/_static/rect_grasp_definition.png differ
diff --git a/docs/source/_static/transformation.png b/docs/source/_static/transformation.png
new file mode 100644
index 0000000..b2e1823
Binary files /dev/null and b/docs/source/_static/transformation.png differ
diff --git a/docs/source/conf.py b/docs/source/conf.py
index 4243d3b..8be07ed 100644
--- a/docs/source/conf.py
+++ b/docs/source/conf.py
@@ -18,11 +18,11 @@
# -- Project information -----------------------------------------------------
project = 'graspnetAPI'
-copyright = '2020, MVIG, Shanghai Jiao Tong University'
+copyright = '2021, MVIG, Shanghai Jiao Tong University'
author = 'graspnet'
# The full version, including alpha/beta/rc tags
-release = '1.2.1'
+release = '1.2.11'
# -- General configuration ---------------------------------------------------
@@ -55,4 +55,4 @@
# relative to this directory. They are copied after the builtin static files,
# so a file named "default.css" will overwrite the builtin "default.css".
html_static_path = ['_static']
-master_doc = 'index'
\ No newline at end of file
+master_doc = 'index'
diff --git a/docs/source/example_eval.rst b/docs/source/example_eval.rst
index 148d3ec..0b29e7f 100644
--- a/docs/source/example_eval.rst
+++ b/docs/source/example_eval.rst
@@ -6,10 +6,22 @@ Evaluation
Data Preparation
^^^^^^^^^^^^^^^^
-The first step of evaluation is to prepare your own data.
+The first step of evaluation is to prepare your own results.
You need to run your code and generate a `GraspGroup` for each image in each scene.
Then call the `save_npy` function of `GraspGroup` to dump the results.
+To generate a `GraspGroup` and save it, you can directly input a 2D numpy array for the `GraspGroup` class:
+::
+
+ gg=GraspGroup(np.array([[score_1, width_1, height_1, depth_1, rotation_matrix_1(9), translation_1(3), object_id_1],
+ [score_2, width_2, height_2, depth_2, rotation_matrix_2(9), translation_2(3), object_id_2],
+ ...,
+ [score_N, width_N, height_N, depth_N, rotation_matrix_N(9), translation_N(3), object_id_N]]
+ ))
+ gg.save_npy(save_path)
+
+where your algorithm predicts N grasp poses for an image. For the `object_id`, you can simply input `0`. For the meaning of other entries, you should refer to the doc for Grasp Label Format-API Loaded Labels
+
The file structure of dump folder should be as follows:
::
@@ -30,7 +42,7 @@ The file structure of dump folder should be as follows:
|
--- scene_0189
-You can only generate dump for one camera, there will be no error for doing that.
+You can choose to generate dump files for only one camera, there will be no error for doing that.
Evaluation API
^^^^^^^^^^^^^^
diff --git a/docs/source/grasp_format.rst b/docs/source/grasp_format.rst
new file mode 100644
index 0000000..8f4d9fe
--- /dev/null
+++ b/docs/source/grasp_format.rst
@@ -0,0 +1,178 @@
+.. grasp_format:
+
+Grasp Label Format
+==================
+
+Raw Label Format
+----------------
+The raw label is composed of two parts, i.e. labels for all grasp candidates on each object and collision masks for each scene.
+
+
+
+Labels on Objects
+^^^^^^^^^^^^^^^^^
+The raw label on each object is a list of numpy arrays.
+
+::
+
+ >>> import numpy as np
+ >>> l = np.load('000_labels.npz') # GRASPNET_ROOT/grasp_label/000_labels.npz
+ >>> l.files
+ ['points', 'offsets', 'collision', 'scores']
+ >>> l['points'].shape
+ (3459, 3)
+ >>> l['offsets'].shape
+ (3459, 300, 12, 4, 3)
+ >>> l['collision'].shape
+ (3459, 300, 12, 4)
+ >>> l['collision'].dtype
+ dtype('bool')
+ >>> l['scores'].shape
+ (3459, 300, 12, 4)
+ >>> l['scores'][0][0][0][0]
+ -1.0
+
+- 'points' records the grasp center point coordinates in model frame.
+
+- 'offsets' records the in-plane rotation, depth and width of the gripper respectively in the last dimension.
+
+- 'collision' records the bool mask for if the grasp pose collides with the model.
+
+- 'scores' records the minimum coefficient of friction between the gripper and object to achieve a stable grasp.
+
+.. note::
+
+ In the raw label, the **lower** score the grasp has, the **better** it is. However, -1.0 score means the grasp pose is totally not acceptable.
+
+300, 12, 4 denote view id, in-plane rotation id and depth id respectively. The views are defined here in graspnetAPI/utils/utils.py.
+
+.. literalinclude:: ../../graspnetAPI/utils/utils.py
+ :lines: 51-58
+ :linenos:
+
+Collision Masks on Each Scene
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+Collision mask on each scene is a list of numpy arrays.
+
+::
+
+ >>> import numpy as np
+ >>> c = np.load('collision_labels.npz') # GRASPNET_ROOT/collision_label/scene_0000/collision_labels.npz
+ >>> c.files
+ ['arr_0', 'arr_4', 'arr_5', 'arr_2', 'arr_3', 'arr_7', 'arr_1', 'arr_8', 'arr_6']
+ >>> c['arr_0'].shape
+ (487, 300, 12, 4)
+ >>> c['arr_0'].dtype
+ dtype('bool')
+ >>> c['arr_0'][10][20][3]
+ array([ True, True, True, True])
+
+'arr_i' is the collision mask for the `i` th object in the `object_id_list.txt` for each scene whose shape is (num_points, 300, 12, 4).
+num_points, 300, 12, 4 denote the number of points in the object, view id, in-plane rotation id and depth id respectively.
+
+Users can refer to :py:func:`graspnetAPI.GraspNet.loadGrasp` for more details of how to use the labels.
+
+API Loaded Labels
+-----------------
+
+Dealing with the raw labels are time-consuming and need high familiarity with graspnet.
+So the API also provides an easy access to the labels.
+
+By calling :py:func:`graspnetAPI.GraspNet.loadGrasp`, users can get all the positive grasp labels in a scene with their parameters and scores.
+
+There are totally four kinds of data structures for loaded grasp labels: **Grasp**, **GraspGroup**, **RectGrasp** and **RectGraspGroup**.
+The internal data format of each class is a numpy array which is more efficient than the Python list.
+Their definitions are given in grasp.py
+
+Example Labels
+^^^^^^^^^^^^^^
+
+Before looking into the details, an example is given below.
+
+Loading a GraspGroup instance.
+
+.. literalinclude:: ../../examples/exam_grasp_format.py
+ :lines: 1-27
+
+Users can access elements by index or slice.
+
+.. literalinclude:: ../../examples/exam_grasp_format.py
+ :lines: 29-35
+
+Each element of GraspGroup is a Grasp instance.
+The properties of Grasp can be accessed via provided methods.
+
+.. literalinclude:: ../../examples/exam_grasp_format.py
+ :lines: 37-46
+
+RectGrasp is the class for rectangle grasps. The format is different from Grasp.
+But the provided APIs are similar.
+
+.. literalinclude:: ../../examples/exam_grasp_format.py
+ :lines: 49-65
+
+6D Grasp
+^^^^^^^^
+Actually, 17 float numbers are used to define a general 6d grasp.
+The width, height, depth, score and attached object id are also part of the definition.
+
+.. note::
+
+ In the loaded label, the **higher** score the grasp has, the **better** it is which is different from raw labels. Actually, score = 1.1 - raw_score (which is the coefficient of friction)
+
+.. literalinclude:: ../../graspnetAPI/graspnet.py
+ :lines: 635-637
+ :emphasize-lines: 2
+
+The detailed defition of each parameter is shown in the figure.
+
+.. image:: _static/grasp_definition.png
+
+.. literalinclude:: ../../graspnetAPI/grasp.py
+ :lines: 14-36
+
+6D Grasp Group
+^^^^^^^^^^^^^^
+
+Usually, there are a lot of grasps in a scene, :py:class:`GraspGroup` is a class for these grasps.
+Compared with :py:class:`Grasp`, :py:class:`GraspGroup` contains a 2D numpy array, the additional dimension is the index for each grasp.
+
+.. literalinclude:: ../../graspnetAPI/grasp.py
+ :lines: 201-218
+
+Common operations on a list such as indexing, slicing and sorting are implemented.
+Besides, one important function is that users can **dump** a GraspGroup into a numpy file and **load** it in another program by calling :py:func:`GraspGroup.save_npy` and :py:func:`GraspGroup.from_npy`.
+
+Rectangle Grasp
+^^^^^^^^^^^^^^^
+7 float numbers are used to define a general rectangle grasp, i.e. the center point, the open point, height, score and the attached object id.
+The detailed definition of each parameter is shown in the figure above and below and the coordinates for center point and open point are in the pixel frame.
+
+.. image:: _static/rect_grasp_definition.png
+
+.. literalinclude:: ../../graspnetAPI/grasp.py
+ :lines: 553-572
+
+Rectangle Grasp Group
+^^^^^^^^^^^^^^^^^^^^^
+
+The format for :py:class:`RectGraspGroup` is similar to that of :py:class:`RectGrasp` and :py:class:`GraspGroup`.
+
+.. literalinclude:: ../../graspnetAPI/grasp.py
+ :lines: 752-769
+
+.. note::
+
+ We recommend users to access and modify the labels by provided functions although users can also manipulate the data directly but it is **Not Recommended**.
+ Please refer to the Python API for more details.
+
+Grasp and GraspGroup Transformation
+-----------------------------------
+
+Users can transform a Grasp or GraspGroup giving a 4x4 matrix.
+
+.. literalinclude:: ../../examples/exam_grasp_format.py
+ :lines: 67-95
+
+.. image:: _static/transformation.png
diff --git a/docs/source/graspnetAPI.utils.dexnet.grasping.meshpy.rst b/docs/source/graspnetAPI.utils.dexnet.grasping.meshpy.rst
new file mode 100644
index 0000000..030be5e
--- /dev/null
+++ b/docs/source/graspnetAPI.utils.dexnet.grasping.meshpy.rst
@@ -0,0 +1,54 @@
+graspnetAPI.utils.dexnet.grasping.meshpy package
+================================================
+
+Submodules
+----------
+
+graspnetAPI.utils.dexnet.grasping.meshpy.mesh module
+----------------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.meshpy.mesh
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+graspnetAPI.utils.dexnet.grasping.meshpy.obj\_file module
+---------------------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.meshpy.obj_file
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+graspnetAPI.utils.dexnet.grasping.meshpy.sdf module
+---------------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.meshpy.sdf
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+graspnetAPI.utils.dexnet.grasping.meshpy.sdf\_file module
+---------------------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.meshpy.sdf_file
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+graspnetAPI.utils.dexnet.grasping.meshpy.stable\_pose module
+------------------------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.meshpy.stable_pose
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+
+Module contents
+---------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.meshpy
+ :members:
+ :undoc-members:
+ :show-inheritance:
diff --git a/docs/source/graspnetAPI.utils.dexnet.grasping.rst b/docs/source/graspnetAPI.utils.dexnet.grasping.rst
new file mode 100644
index 0000000..8bb4be8
--- /dev/null
+++ b/docs/source/graspnetAPI.utils.dexnet.grasping.rst
@@ -0,0 +1,70 @@
+graspnetAPI.utils.dexnet.grasping package
+=========================================
+
+Subpackages
+-----------
+
+.. toctree::
+ :maxdepth: 4
+
+ graspnetAPI.utils.dexnet.grasping.meshpy
+
+Submodules
+----------
+
+graspnetAPI.utils.dexnet.grasping.contacts module
+-------------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.contacts
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+graspnetAPI.utils.dexnet.grasping.grasp module
+----------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.grasp
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+graspnetAPI.utils.dexnet.grasping.grasp\_quality\_config module
+---------------------------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.grasp_quality_config
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+graspnetAPI.utils.dexnet.grasping.grasp\_quality\_function module
+-----------------------------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.grasp_quality_function
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+graspnetAPI.utils.dexnet.grasping.graspable\_object module
+----------------------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.graspable_object
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+graspnetAPI.utils.dexnet.grasping.quality module
+------------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping.quality
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+
+Module contents
+---------------
+
+.. automodule:: graspnetAPI.utils.dexnet.grasping
+ :members:
+ :undoc-members:
+ :show-inheritance:
diff --git a/docs/source/graspnetAPI.utils.dexnet.rst b/docs/source/graspnetAPI.utils.dexnet.rst
new file mode 100644
index 0000000..f1f2883
--- /dev/null
+++ b/docs/source/graspnetAPI.utils.dexnet.rst
@@ -0,0 +1,38 @@
+graspnetAPI.utils.dexnet package
+================================
+
+Subpackages
+-----------
+
+.. toctree::
+ :maxdepth: 4
+
+ graspnetAPI.utils.dexnet.grasping
+
+Submodules
+----------
+
+graspnetAPI.utils.dexnet.abstractstatic module
+----------------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.abstractstatic
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+graspnetAPI.utils.dexnet.constants module
+-----------------------------------------
+
+.. automodule:: graspnetAPI.utils.dexnet.constants
+ :members:
+ :undoc-members:
+ :show-inheritance:
+
+
+Module contents
+---------------
+
+.. automodule:: graspnetAPI.utils.dexnet
+ :members:
+ :undoc-members:
+ :show-inheritance:
diff --git a/docs/source/graspnetAPI.utils.rst b/docs/source/graspnetAPI.utils.rst
index 7fba83f..f0bbcd9 100644
--- a/docs/source/graspnetAPI.utils.rst
+++ b/docs/source/graspnetAPI.utils.rst
@@ -1,6 +1,14 @@
graspnetAPI.utils package
=========================
+Subpackages
+-----------
+
+.. toctree::
+ :maxdepth: 4
+
+ graspnetAPI.utils.dexnet
+
Submodules
----------
diff --git a/docs/source/index.rst b/docs/source/index.rst
index b143292..befb5a4 100644
--- a/docs/source/index.rst
+++ b/docs/source/index.rst
@@ -12,6 +12,7 @@ Welcome to graspnetAPI's documentation!
about
install
+ grasp_format
Examples
=========
diff --git a/docs/source/install.rst b/docs/source/install.rst
index b673bfe..f98bc98 100644
--- a/docs/source/install.rst
+++ b/docs/source/install.rst
@@ -44,13 +44,13 @@ Dexnet Model Cache
------------------
Dexnet model cache is optional without which the evaluation will be much slower(about 10x time slower).
-You can both download the file or generate it by yourself by running gen_pickle_dexmodel.py_.
+You can both download the file or generate it by yourself by running gen_pickle_dexmodel.py_(recommended).
.. _gen_pickle_dexmodel.py: https://github.com/graspnet/graspnetAPI/blob/master/gen_pickle_dexmodel.py
Install API
^^^^^^^^^^^
-You may install usign pip::
+You may install using pip::
pip install graspnetAPI
diff --git a/examples/exam_check_data.py b/examples/exam_check_data.py
index ab42368..9fa0916 100644
--- a/examples/exam_check_data.py
+++ b/examples/exam_check_data.py
@@ -19,4 +19,4 @@
g = GraspNet(graspnet_root, 'realsense', 'all')
if g.checkDataCompleteness():
- print('Check for kinect passed')
\ No newline at end of file
+ print('Check for realsense passed')
diff --git a/examples/exam_grasp_format.py b/examples/exam_grasp_format.py
new file mode 100644
index 0000000..a3c72a3
--- /dev/null
+++ b/examples/exam_grasp_format.py
@@ -0,0 +1,95 @@
+__author__ = 'mhgou'
+__version__ = '1.0'
+
+from graspnetAPI import GraspNet, Grasp, GraspGroup
+import open3d as o3d
+import cv2
+import numpy as np
+
+# GraspNetAPI example for loading grasp for a scene.
+# change the graspnet_root path
+
+####################################################################
+graspnet_root = '/disk1/graspnet' # ROOT PATH FOR GRASPNET
+####################################################################
+
+sceneId = 1
+annId = 3
+
+# initialize a GraspNet instance
+g = GraspNet(graspnet_root, camera='kinect', split='train')
+
+# load grasps of scene 1 with annotation id = 3, camera = kinect and fric_coef_thresh = 0.2
+_6d_grasp = g.loadGrasp(sceneId = sceneId, annId = annId, format = '6d', camera = 'kinect', fric_coef_thresh = 0.2)
+print('6d grasp:\n{}'.format(_6d_grasp))
+
+# _6d_grasp is an GraspGroup instance defined in grasp.py
+print('_6d_grasp:\n{}'.format(_6d_grasp))
+
+# index
+grasp = _6d_grasp[0]
+print('_6d_grasp[0](grasp):\n{}'.format(grasp))
+
+# slice
+print('_6d_grasp[0:2]:\n{}'.format(_6d_grasp[0:2]))
+print('_6d_grasp[[0,1]]:\n{}'.format(_6d_grasp[[0,1]]))
+
+# grasp is a Grasp instance defined in grasp.py
+# access and set properties
+print('grasp.translation={}'.format(grasp.translation))
+grasp.translation = np.array([1.0, 2.0, 3.0])
+print('After modification, grasp.translation={}'.format(grasp.translation))
+print('grasp.rotation_matrix={}'.format(grasp.rotation_matrix))
+grasp.rotation_matrix = np.eye(3).reshape((9))
+print('After modification, grasp.rotation_matrix={}'.format(grasp.rotation_matrix))
+print('grasp.width={}, height:{}, depth:{}, score:{}'.format(grasp.width, grasp.height, grasp.depth, grasp.score))
+print('More operation on Grasp and GraspGroup can be seen in the API document')
+
+
+# load rectangle grasps of scene 1 with annotation id = 3, camera = realsense and fric_coef_thresh = 0.2
+rect_grasp_group = g.loadGrasp(sceneId = sceneId, annId = annId, format = 'rect', camera = 'realsense', fric_coef_thresh = 0.2)
+print('rectangle grasp group:\n{}'.format(rect_grasp_group))
+
+# rect_grasp is an RectGraspGroup instance defined in grasp.py
+print('rect_grasp_group:\n{}'.format(rect_grasp_group))
+
+# index
+rect_grasp = rect_grasp_group[0]
+print('rect_grasp_group[0](rect_grasp):\n{}'.format(rect_grasp))
+
+# slice
+print('rect_grasp_group[0:2]:\n{}'.format(rect_grasp_group[0:2]))
+print('rect_grasp_group[[0,1]]:\n{}'.format(rect_grasp_group[[0,1]]))
+
+# properties of rect_grasp
+print('rect_grasp.center_point:{}, open_point:{}, height:{}, score:{}'.format(rect_grasp.center_point, rect_grasp.open_point, rect_grasp.height, rect_grasp.score))
+
+# transform grasp
+g = Grasp() # simple Grasp
+frame = o3d.geometry.TriangleMesh.create_coordinate_frame(0.1)
+
+# Grasp before transformation
+o3d.visualization.draw_geometries([g.to_open3d_geometry(), frame])
+g.translation = np.array((0,0,0.01))
+
+# setup a transformation matrix
+T = np.eye(4)
+T[:3,3] = np.array((0.01, 0.02, 0.03))
+T[:3,:3] = np.array([[0,0,1.0],[1,0,0],[0,1,0]])
+g.transform(T)
+
+# Grasp after transformation
+o3d.visualization.draw_geometries([g.to_open3d_geometry(), frame])
+
+g1 = Grasp()
+gg = GraspGroup()
+gg.add(g)
+gg.add(g1)
+
+# GraspGroup before transformation
+o3d.visualization.draw_geometries([*gg.to_open3d_geometry_list(), frame])
+
+gg.transform(T)
+
+# GraspGroup after transformation
+o3d.visualization.draw_geometries([*gg.to_open3d_geometry_list(), frame])
\ No newline at end of file
diff --git a/grasp_definition.png b/grasp_definition.png
index 27a56d6..bd6e4f5 100644
Binary files a/grasp_definition.png and b/grasp_definition.png differ
diff --git a/graspnetAPI/__init__.py b/graspnetAPI/__init__.py
index 4911dbc..b33e391 100644
--- a/graspnetAPI/__init__.py
+++ b/graspnetAPI/__init__.py
@@ -1,6 +1,6 @@
__author__ = 'mhgou'
-__version__ = '1.0'
+__version__ = '1.2.11'
from .graspnet import GraspNet
from .graspnet_eval import GraspNetEval
-from .grasp import Grasp, GraspGroup, RectGrasp, RectGraspGroup
\ No newline at end of file
+from .grasp import Grasp, GraspGroup, RectGrasp, RectGraspGroup
diff --git a/graspnetAPI/grasp.py b/graspnetAPI/grasp.py
index 042ab70..c385443 100644
--- a/graspnetAPI/grasp.py
+++ b/graspnetAPI/grasp.py
@@ -1,5 +1,4 @@
__author__ = 'mhgou'
-__version__ = '1.0'
import numpy as np
import open3d as o3d
@@ -130,7 +129,7 @@ def rotation_matrix(self, *args):
- len(args) == 9: float of matrix
'''
if len(args) == 1:
- self.grasp_array[4:13] = np.array(args[0],dtype = np.float64)
+ self.grasp_array[4:13] = np.array(args[0],dtype = np.float64).reshape(9)
elif len(args) == 9:
self.grasp_array[4:13] = np.array(args,dtype = np.float64)
@@ -169,19 +168,39 @@ def object_id(self):
@object_id.setter
def object_id(self, object_id):
'''
- **input:**
+ **Input:**
- int of the object_id.
'''
self.grasp_array[16] = object_id
- def to_open3d_geometry(self):
+ def transform(self, T):
+ '''
+ **Input:**
+
+ - T: np.array of shape (4, 4)
+
+ **Output:**
+
+ - Grasp instance after transformation, the original Grasp will also be changed.
+ '''
+ rotation = T[:3,:3]
+ translation = T[:3,3]
+ self.translation = np.dot(rotation, self.translation.reshape((3,1))).reshape(-1) + translation
+ self.rotation_matrix = np.dot(rotation, self.rotation_matrix)
+ return self
+
+ def to_open3d_geometry(self, color=None):
'''
+ **Input:**
+
+ - color: optional, tuple of shape (3) denotes (r, g, b), e.g., (1,0,0) for red
+
**Ouput:**
- list of open3d.geometry.Geometry of the gripper.
'''
- return plot_gripper_pro_max(self.translation, self.rotation_matrix, self.width, self.depth, score = self.score)
+ return plot_gripper_pro_max(self.translation, self.rotation_matrix, self.width, self.depth, score = self.score, color = color)
class GraspGroup():
def __init__(self, *args):
@@ -369,7 +388,7 @@ def object_ids(self):
- numpy array of shape (-1, ) of the object ids.
'''
- return self.grasp_group_array[:,16].astype(np.int32)
+ return self.grasp_group_array[:,16]
@object_ids.setter
def object_ids(self, object_ids):
@@ -381,6 +400,22 @@ def object_ids(self, object_ids):
assert object_ids.size == len(self)
self.grasp_group_array[:,16] = copy.deepcopy(object_ids)
+ def transform(self, T):
+ '''
+ **Input:**
+
+ - T: np.array of shape (4, 4)
+
+ **Output:**
+
+ - GraspGroup instance after transformation, the original GraspGroup will also be changed.
+ '''
+ rotation = T[:3,:3]
+ translation = T[:3,3]
+ self.translations = np.dot(rotation, self.translations.T).T + translation # (-1, 3)
+ self.rotation_matrices = np.matmul(rotation, self.rotation_matrices).reshape((-1, 3, 3)) # (-1, 9)
+ return self
+
def add(self, element):
'''
**Input:**
@@ -955,7 +990,8 @@ def batch_get_key_points(self):
norm_open_point_vector = np.linalg.norm(open_point_vector, axis = 1).reshape(-1, 1)
unit_open_point_vector = open_point_vector / np.hstack((norm_open_point_vector, norm_open_point_vector)) # (-1, 2)
counter_clock_wise_rotation_matrix = np.array([[0,-1], [1, 0]])
- upper_points = np.dot(counter_clock_wise_rotation_matrix, unit_open_point_vector.reshape(-1, 2, 1)).reshape(-1, 2) * np.hstack([heights, heights]) / 2 + centers # (-1, 2)
+ # upper_points = np.dot(counter_clock_wise_rotation_matrix, unit_open_point_vector.reshape(-1, 2, 1)).reshape(-1, 2) * np.hstack([heights, heights]) / 2 + centers # (-1, 2)
+ upper_points = np.einsum('ij,njk->nik', counter_clock_wise_rotation_matrix, unit_open_point_vector.reshape(-1, 2, 1)).reshape(-1, 2) * np.hstack([heights, heights]) / 2 + centers # (-1, 2)
return centers, open_points, upper_points
def to_grasp_group(self, camera, depths, depth_method = batch_center_depth):
@@ -1042,4 +1078,4 @@ def random_sample(self, numGrasp = 20):
np.random.shuffle(shuffled_rect_grasp_group_array)
shuffled_rect_grasp_group = RectGraspGroup()
shuffled_rect_grasp_group.rect_grasp_group_array = copy.deepcopy(shuffled_rect_grasp_group_array[:numGrasp])
- return shuffled_rect_grasp_group
\ No newline at end of file
+ return shuffled_rect_grasp_group
diff --git a/graspnetAPI/graspnet.py b/graspnetAPI/graspnet.py
index f63417a..a9cebc0 100755
--- a/graspnetAPI/graspnet.py
+++ b/graspnetAPI/graspnet.py
@@ -1,5 +1,4 @@
__author__ = 'hsfang, mhgou, cxwang'
-__version__ = '1.0'
# Interface for accessing the GraspNet-1Billion dataset.
# Description and part of the codes modified from MSCOCO api
@@ -68,7 +67,7 @@ def _isArrayLike(obj):
class GraspNet():
- def __init__(self, root, camera='kinect', split='train'):
+ def __init__(self, root, camera='kinect', split='train', sceneIds=[]):
'''
graspnetAPI main class.
@@ -77,10 +76,12 @@ def __init__(self, root, camera='kinect', split='train'):
- camera: string of type of camera: "kinect" or "realsense"
- - split: string of type of split of dataset: "all", "train", "test", "test_seen", "test_similar" or "test_novel"
+ - split: string of type of split of dataset: "all", "train", "test", "test_seen", "test_similar", "test_novel" or "custom"
+
+ - sceneIds: list of custom scene ids.
'''
assert camera in ['kinect', 'realsense'], 'camera should be kinect or realsense'
- assert split in ['all', 'train', 'test', 'test_seen', 'test_similar', 'test_novel'], 'split should be all/train/test/test_seen/test_similar/test_novel'
+ assert split in ['all', 'train', 'test', 'test_seen', 'test_similar', 'test_novel', "custom"], 'split should be all/train/test/test_seen/test_similar/test_novel'
self.root = root
self.camera = camera
self.split = split
@@ -98,6 +99,8 @@ def __init__(self, root, camera='kinect', split='train'):
self.sceneIds = list(range(130, 160))
elif split == 'test_novel':
self.sceneIds = list(range(160, 190))
+ elif split == "custom":
+ self.sceneIds = sceneIds
self.rgbPath = []
self.depthPath = []
@@ -435,7 +438,7 @@ def loadWorkSpace(self, sceneId, camera, annId):
y2 = len(masky) - np.argmax(masky[::-1])
return (x1, y1, x2, y2)
- def loadScenePointCloud(self, sceneId, camera, annId, align=False, format='open3d', use_workspace=False):
+ def loadScenePointCloud(self, sceneId, camera, annId, align=False, format = 'open3d', use_workspace = False, use_mask = True, use_inpainting = False):
'''
**Input:**
@@ -451,6 +454,10 @@ def loadScenePointCloud(self, sceneId, camera, annId, align=False, format='open3
- use_workspace: bool of whether crop the point cloud in the work space.
+ - use_mask: bool of whether crop the point cloud use mask(z>0), only open3d 0.9.0 is supported for False option.
+ Only turn to False if you know what you are doing.
+
+ - use_inpainting: bool of whether inpaint the depth image for the missing information.
**Output:**
@@ -460,6 +467,11 @@ def loadScenePointCloud(self, sceneId, camera, annId, align=False, format='open3
'''
colors = self.loadRGB(sceneId = sceneId, camera = camera, annId = annId).astype(np.float32) / 255.0
depths = self.loadDepth(sceneId = sceneId, camera = camera, annId = annId)
+ if use_inpainting:
+ fault_mask = depths < 200
+ depths[fault_mask] = 0
+ inpainting_mask = (np.abs(depths) < 10).astype(np.uint8)
+ depths = cv2.inpaint(depths, inpainting_mask, 5, cv2.INPAINT_NS)
intrinsics = np.load(os.path.join(self.root, 'scenes', 'scene_%04d' % sceneId, camera, 'camK.npy'))
fx, fy = intrinsics[0,0], intrinsics[1,1]
cx, cy = intrinsics[0,2], intrinsics[1,2]
@@ -477,7 +489,9 @@ def loadScenePointCloud(self, sceneId, camera, annId, align=False, format='open3
points_z = depths / s
points_x = (xmap - cx) / fx * points_z
points_y = (ymap - cy) / fy * points_z
-
+ # print(f'points_x.shape:{points_x.shape}')
+ # print(f'points_y.shape:{points_y.shape}')
+ # print(f'points_z.shape:{points_z.shape}')
if use_workspace:
(x1, y1, x2, y2) = self.loadWorkSpace(sceneId, camera, annId)
points_z = points_z[y1:y2,x1:x2]
@@ -487,8 +501,13 @@ def loadScenePointCloud(self, sceneId, camera, annId, align=False, format='open3
mask = (points_z > 0)
points = np.stack([points_x, points_y, points_z], axis=-1)
- points = points[mask]
- colors = colors[mask]
+ # print(f'points.shape:{points.shape}')
+ if use_mask:
+ points = points[mask]
+ colors = colors[mask]
+ else:
+ points = points.reshape((-1, 3))
+ colors = colors.reshape((-1, 3))
if align:
points = transform_points(points, camera_pose)
if format == 'open3d':
@@ -643,17 +662,9 @@ def loadGrasp(self, sceneId, annId=0, format = '6d', camera='kinect', grasp_labe
grasp_group.grasp_group_array = np.concatenate((grasp_group.grasp_group_array, obj_grasp_array))
return grasp_group
else:
- import copy
# 'rect'
- # for rectangle grasp, collision labels and grasp labels are not necessray.
- ##################### OLD LABEL ################
- ############### MODIFICATION NEEDED ############
- rect_grasp_label = np.load(os.path.join(self.root,'scenes','scene_%04d' % sceneId,camera,'rect','%04d.npy' % annId))
- mask = rect_grasp_label[:,5] >= (1.1 - fric_coef_thresh)
- rect_grasp_label = rect_grasp_label[mask]
- rect_grasp = RectGraspGroup()
- rect_grasp.rect_grasp_group_array = copy.deepcopy(rect_grasp_label)
- return rect_grasp
+ rect_grasps = RectGraspGroup(os.path.join(self.root,'scenes','scene_%04d' % sceneId,camera,'rect','%04d.npy' % annId))
+ return rect_grasps
def loadData(self, ids=None, *extargs):
'''
@@ -694,7 +705,7 @@ def loadData(self, ids=None, *extargs):
scene_name = 'scene_'+str(sceneId).zfill(4)
return (rgbPath, depthPath, segLabelPath, metaPath, rectLabelPath, scene_name,annId)
- def showObjGrasp(self, objIds=[], numGrasp=10, th=0.5, saveFolder='save_fig', show=False):
+ def showObjGrasp(self, objIds=[], numGrasp=10, th=0.5, maxWidth=0.08, saveFolder='save_fig', show=False):
'''
**Input:**
@@ -704,6 +715,8 @@ def showObjGrasp(self, objIds=[], numGrasp=10, th=0.5, saveFolder='save_fig', sh
- th: threshold of the coefficient of friction.
+ - maxWidth: float, only visualize grasps with width<=maxWidth
+
- saveFolder: string of the path to save the rendered image.
- show: bool of whether to show the image.
@@ -721,7 +734,7 @@ def showObjGrasp(self, objIds=[], numGrasp=10, th=0.5, saveFolder='save_fig', sh
if not os.path.exists(saveFolder):
os.mkdir(saveFolder)
for obj_id in objIds:
- visObjGrasp(self.root, obj_id, num_grasp=numGrasp,th=th, save_folder=saveFolder, show=show)
+ visObjGrasp(self.root, obj_id, num_grasp=numGrasp, th=th, max_width=maxWidth, save_folder=saveFolder, show=show)
def showSceneGrasp(self, sceneId, camera = 'kinect', annId = 0, format = '6d', numGrasp = 20, show_object = True, coef_fric_thresh = 0.1):
'''
@@ -737,7 +750,7 @@ def showSceneGrasp(self, sceneId, camera = 'kinect', annId = 0, format = '6d', n
- numGrasp: int of the displayed grasp number, grasps will be randomly sampled.
- - coef_fric_thresh: float of the friction coefficient of grasps.
+ - coef_fric_thresh: float of the friction coefficient of grasps.
'''
if format == '6d':
geometries = []
@@ -759,7 +772,7 @@ def showSceneGrasp(self, sceneId, camera = 'kinect', annId = 0, format = '6d', n
cv2.waitKey(0)
cv2.destroyAllWindows()
- def show6DPose(self, sceneIds, saveFolder='save_fig', show=False):
+ def show6DPose(self, sceneIds, saveFolder='save_fig', show=False, perObj=False):
'''
**Input:**
@@ -769,6 +782,8 @@ def show6DPose(self, sceneIds, saveFolder='save_fig', show=False):
- show: bool of whether to show the image.
+ - perObj: bool, show grasps on each object
+
**Output:**
- No output but to save the rendered image and maybe show the result.
@@ -783,4 +798,4 @@ def show6DPose(self, sceneIds, saveFolder='save_fig', show=False):
for scene_id in sceneIds:
scene_name = 'scene_'+str(scene_id).zfill(4)
vis6D(self.root, scene_name, 0, self.camera,
- align_to_table=True, save_folder=saveFolder, show=show)
+ align_to_table=True, save_folder=saveFolder, show=show, per_obj=perObj)
diff --git a/graspnetAPI/graspnet_eval.py b/graspnetAPI/graspnet_eval.py
index ae2f81d..a8880c9 100644
--- a/graspnetAPI/graspnet_eval.py
+++ b/graspnetAPI/graspnet_eval.py
@@ -1,5 +1,4 @@
__author__ = 'mhgou, cxwang and hsfang'
-__version__ = '1.0'
import numpy as np
import os
@@ -92,7 +91,7 @@ def get_model_poses(self, scene_id, ann_id):
pose_list.append(mat)
return obj_list, pose_list, camera_pose, align_mat
- def eval_scene(self, scene_id, dump_folder, return_list = False,vis = False):
+ def eval_scene(self, scene_id, dump_folder, TOP_K = 50, return_list = False,vis = False, max_width = 0.1):
'''
**Input:**
@@ -100,17 +99,21 @@ def eval_scene(self, scene_id, dump_folder, return_list = False,vis = False):
- dump_folder: string of the folder that saves the dumped npy files.
+ - TOP_K: int of the top number of grasp to evaluate
+
- return_list: bool of whether to return the result list.
- vis: bool of whether to show the result
+ - max_width: float of the maximum gripper width in evaluation
+
**Output:**
- scene_accuracy: np.array of shape (256, 50, 6) of the accuracy tensor.
'''
config = get_config()
table = create_table_points(1.0, 1.0, 0.05, dx=-0.5, dy=-0.5, dz=-0.05, grid_size=0.008)
- TOP_K = 50
+
list_coe_of_friction = [0.2,0.4,0.6,0.8,1.0,1.2]
model_list, dexmodel_list, _ = self.get_scene_models(scene_id, ann_id=0)
@@ -130,14 +133,31 @@ def eval_scene(self, scene_id, dump_folder, return_list = False,vis = False):
_, pose_list, camera_pose, align_mat = self.get_model_poses(scene_id, ann_id)
table_trans = transform_points(table, np.linalg.inv(np.matmul(align_mat, camera_pose)))
- grasp_list, score_list, collision_mask_list = eval_grasp(grasp_group, model_sampled_list, dexmodel_list, pose_list, config, table=table_trans, voxel_size=0.008)
+ # clip width to [0,max_width]
+ gg_array = grasp_group.grasp_group_array
+ min_width_mask = (gg_array[:,1] < 0)
+ max_width_mask = (gg_array[:,1] > max_width)
+ gg_array[min_width_mask,1] = 0
+ gg_array[max_width_mask,1] = max_width
+ grasp_group.grasp_group_array = gg_array
+
+ grasp_list, score_list, collision_mask_list = eval_grasp(grasp_group, model_sampled_list, dexmodel_list, pose_list, config, table=table_trans, voxel_size=0.008, TOP_K = TOP_K)
- # concat into scene level
# remove empty
- grasp_list = [x for x in grasp_list if len(x[0])!= 0]
- score_list = [x for x in score_list if len(x)!=0]
+ grasp_list = [x for x in grasp_list if len(x) != 0]
+ score_list = [x for x in score_list if len(x) != 0]
collision_mask_list = [x for x in collision_mask_list if len(x)!=0]
+ if len(grasp_list) == 0:
+ grasp_accuracy = np.zeros((TOP_K,len(list_coe_of_friction)))
+ scene_accuracy.append(grasp_accuracy)
+ grasp_list_list.append([])
+ score_list_list.append([])
+ collision_list_list.append([])
+ print('\rMean Accuracy for scene:{} ann:{}='.format(scene_id, ann_id),np.mean(grasp_accuracy[:,:]), end='')
+ continue
+
+ # concat into scene level
grasp_list, score_list, collision_mask_list = np.concatenate(grasp_list), np.concatenate(score_list), np.concatenate(collision_mask_list)
if vis:
@@ -176,7 +196,7 @@ def eval_scene(self, scene_id, dump_folder, return_list = False,vis = False):
else:
grasp_accuracy[k,fric_idx] = np.sum(((score_list[0:k+1]<=fric) & (score_list[0:k+1]>0)).astype(int))/(k+1)
- print('\rMean Accuracy for scene:%04d ann:%04d = %.3f' % (scene_id, ann_id, 100.0 * np.mean(grasp_accuracy[:,:])), end='')
+ print('\rMean Accuracy for scene:%04d ann:%04d = %.3f' % (scene_id, ann_id, 100.0 * np.mean(grasp_accuracy[:,:])), end='', flush=True)
scene_accuracy.append(grasp_accuracy)
if not return_list:
return scene_accuracy
@@ -225,7 +245,7 @@ def eval_seen(self, dump_folder, proc = 2):
'''
res = np.array(self.parallel_eval_scenes(scene_ids = list(range(100, 130)), dump_folder = dump_folder, proc = proc))
ap = np.mean(res)
- print('\nEvaluation Result:\n----------\n{}, AP={}, AP Seen={}'.format(self.camera, ap, ap))
+ print('\nEvaluation Result:\n----------\n{}, AP Seen={}'.format(self.camera, ap))
return res, ap
def eval_similar(self, dump_folder, proc = 2):
diff --git a/graspnetAPI/utils/eval_utils.py b/graspnetAPI/utils/eval_utils.py
index 7812b77..1ff4f46 100644
--- a/graspnetAPI/utils/eval_utils.py
+++ b/graspnetAPI/utils/eval_utils.py
@@ -1,3 +1,6 @@
+__author__ = 'cxwang, mhgou'
+__version__ = '1.0'
+
import os
import time
import numpy as np
@@ -17,11 +20,9 @@
def get_scene_name(num):
'''
**Input:**
-
- num: int of the scene number.
**Output:**
-
- string of the scene name.
'''
return ('scene_%04d' % (num,))
@@ -29,15 +30,10 @@ def get_scene_name(num):
def create_table_points(lx, ly, lz, dx=0, dy=0, dz=0, grid_size=0.01):
'''
**Input:**
-
- lx:
-
- ly:
-
- lz:
-
**Output:**
-
- numpy array of the points with shape (-1, 3).
'''
xmap = np.linspace(0, lx, int(lx/grid_size))
@@ -54,13 +50,9 @@ def create_table_points(lx, ly, lz, dx=0, dy=0, dz=0, grid_size=0.01):
def parse_posevector(posevector):
'''
**Input:**
-
- posevector: list of pose
-
**Output:**
-
- obj_idx: int of the index of object.
-
- mat: numpy array of shape (4, 4) of the 6D pose of object.
'''
mat = np.zeros([4,4],dtype=np.float32)
@@ -81,7 +73,6 @@ def load_dexnet_model(data_path):
- data_path: path to load .obj & .sdf files
**Output:**
-
- obj: dexnet model
'''
of = ObjFile('{}.obj'.format(data_path))
@@ -100,7 +91,6 @@ def transform_points(points, trans):
- trans: (4, 4)
**Output:**
-
- points_trans: (N, 3)
'''
ones = np.ones([points.shape[0],1], dtype=points.dtype)
@@ -112,13 +102,11 @@ def transform_points(points, trans):
def compute_point_distance(A, B):
'''
**Input:**
-
- A: (N, 3)
- B: (M, 3)
**Output:**
-
- dists: (N, M)
'''
A = A[:, np.newaxis, :]
@@ -182,15 +170,12 @@ def get_grasp_score(grasp, obj, fc_list, force_closure_quality_config):
quality = -1
for ind_, value_fc in enumerate(fc_list):
value_fc = round(value_fc, 2)
- # print(value_fc)
tmp = is_force_closure
is_force_closure = PointGraspMetrics3D.grasp_quality(grasp, obj, force_closure_quality_config[value_fc])
if tmp and not is_force_closure:
- # print(value_fc)
quality = round(fc_list[ind_ - 1], 2)
break
elif is_force_closure and value_fc == fc_list[-1]:
- # print(value_fc)
quality = value_fc
break
elif value_fc == fc_list[0] and not is_force_closure:
@@ -201,23 +186,29 @@ def collision_detection(grasp_list, model_list, dexnet_models, poses, scene_poin
'''
**Input:**
- - grasp_list: [(k1,17), (k2,17), ..., (kn,17)] in camera coordinate
+ - grasp_list: [(k1, 17), (k2, 17), ..., (kn, 17)] in camera coordinate
- model_list: [(N1, 3), (N2, 3), ..., (Nn, 3)] in camera coordinate
- - dexnet_models: [GraspableObject3D,] in model coordinate
+ - dexnet_models: [GraspableObject3D,] in object coordinate
- poses: [(4, 4),] from model coordinate to camera coordinate
- scene_points: (Ns, 3) in camera coordinate
+ - outlier: float, used to compute workspace mask
+
- empty_thresh: int, 'num_inner_points < empty_thresh' means empty grasp
+
+ - return_dexgrasps: bool, return grasps in dex-net format while True
**Output:**
- collsion_mask_list: [(k1,), (k2,), ..., (kn,)]
+
+ - empty_mask_list: [(k1,), (k2,), ..., (kn,)]
- - contact_list: [[[ParallelJawPtGrasp3D, Contact3D, Contact3D],],]in model coordinate
+ - dexgrasp_list: [[ParallelJawPtGrasp3D,],] in object coordinate
'''
height = 0.02
depth_base = 0.02
@@ -228,27 +219,24 @@ def collision_detection(grasp_list, model_list, dexnet_models, poses, scene_poin
dexgrasp_list = list()
for i in range(num_models):
- if len(grasp_list[i][0]) == 0:
+ if len(grasp_list[i]) == 0:
collision_mask_list.append(list())
empty_mask_list.append(list())
if return_dexgrasps:
dexgrasp_list.append(list())
continue
+ ## parse grasp parameters
model = model_list[i]
obj_pose = poses[i]
dexnet_model = dexnet_models[i]
grasps = grasp_list[i]
- # print('grasps shape: ', grasps.shape)
grasp_points = grasps[:, 13:16]
- # grasp_towards = grasps[:, 5:8]
- # grasp_angles = grasps[:, 8]
grasp_poses = grasps[:, 4:13].reshape([-1,3,3])
grasp_depths = grasps[:, 3]
grasp_widths = grasps[:, 1]
- # grasp_widths = np.ones(grasps.shape[0])*0.1
- # grasp_points = transform_points(grasp_points, obj_pose)
- # crop scene, remove outlier
+
+ ## crop scene, remove outlier
xmin, xmax = model[:,0].min(), model[:,0].max()
ymin, ymax = model[:,1].min(), model[:,1].max()
zmin, zmax = model[:,2].min(), model[:,2].max()
@@ -256,17 +244,12 @@ def collision_detection(grasp_list, model_list, dexnet_models, poses, scene_poin
ylim = ((scene_points[:,1] > ymin-outlier) & (scene_points[:,1] < ymax+outlier))
zlim = ((scene_points[:,2] > zmin-outlier) & (scene_points[:,2] < zmax+outlier))
workspace = scene_points[xlim & ylim & zlim]
- # print('workspace shape: ', workspace.shape)
- # print(xmin,xmax,ymin,ymax,zmin,zmax)
- # print(grasp_points)
+
# transform scene to gripper frame
target = (workspace[np.newaxis,:,:] - grasp_points[:,np.newaxis,:])
- #grasp_angles = grasp_angles.reshape(-1)
- # grasp_poses = batch_viewpoint_params_to_matrix(grasp_towards, grasp_angles) # gripper to camera coordinate
- # print('target shape 0: ', target.shape)
target = np.matmul(target, grasp_poses)
- # print('target shape: ', target.shape)
- # collision detection
+
+ # compute collision mask
mask1 = ((target[:,:,2]>-height/2) & (target[:,:,2]-depth_base) & (target[:,:,0]-(grasp_widths[:,np.newaxis]/2+finger_width))
@@ -274,7 +257,7 @@ def collision_detection(grasp_list, model_list, dexnet_models, poses, scene_poin
mask5 = (target[:,:,1]<(grasp_widths[:,np.newaxis]/2+finger_width))
mask6 = (target[:,:,1]>grasp_widths[:,np.newaxis]/2)
mask7 = ((target[:,:,0]>-(depth_base+finger_width)) & (target[:,:,0]<-depth_base))
- # print('single mask 1-7 sum:', np.sum(mask1), np.sum(mask2), np.sum(mask3), np.sum(mask4), np.sum(mask5), np.sum(mask6), np.sum(mask7))
+
left_mask = (mask1 & mask2 & mask3 & mask4)
right_mask = (mask1 & mask2 & mask5 & mask6)
bottom_mask = (mask1 & mask3 & mask5 & mask7)
@@ -285,43 +268,26 @@ def collision_detection(grasp_list, model_list, dexnet_models, poses, scene_poin
collision_mask_list.append(collision_mask)
empty_mask_list.append(empty_mask)
+ ## generate grasps in dex-net format
if return_dexgrasps:
dexgrasps = list()
- # points_in_gripper_mask = (mask1 & mask2 &(~mask4) & (~mask6))
- # print('mask sum ', np.sum(points_in_gripper_mask))
for grasp_id,_ in enumerate(grasps):
grasp_point = grasp_points[grasp_id]
R = grasp_poses[grasp_id]
width = grasp_widths[grasp_id]
depth = grasp_depths[grasp_id]
points_in_gripper = target[grasp_id][inner_mask[grasp_id]]
- # print('points in gripper: ', points_in_gripper.shape)
- # if len(points_in_gripper) < 10:
if empty_mask[grasp_id]:
dexgrasps.append(None)
continue
- # c1_ind = np.argmin(points_in_gripper[:, 1])
- # c2_ind = np.argmax(points_in_gripper[:, 1])
- # c1 = points_in_gripper[c1_ind].reshape([3, 1]) # gripper coordinate
- # c2 = points_in_gripper[c2_ind].reshape([3, 1])
- # # print('contacts before trans', c1, c2)
- # c1 = np.dot(R, c1).reshape([3]) + grasp_point # camera coordinate
- # c1 = transform_points(c1[np.newaxis,:], np.linalg.inv(obj_pose)).reshape([3]) # model coordinate
- # c2 = np.dot(R, c2).reshape([3])+ grasp_point # camera coordinate
- # c2 = transform_points(c2[np.newaxis,:], np.linalg.inv(obj_pose)).reshape([3]) # model coordinate
- # print('contacts after trans', c1, c2)
center = np.array([depth, 0, 0]).reshape([3, 1]) # gripper coordinate
center = np.dot(grasp_poses[grasp_id], center).reshape([3])
center = (center + grasp_point).reshape([1,3]) # camera coordinate
- center = transform_points(center, np.linalg.inv(obj_pose)).reshape([3]) # model coordinate
+ center = transform_points(center, np.linalg.inv(obj_pose)).reshape([3]) # object coordinate
R = np.dot(obj_pose[:3,:3].T, R)
binormal, approach_angle = matrix_to_dexnet_params(R)
grasp = ParallelJawPtGrasp3D(ParallelJawPtGrasp3D.configuration_from_params(
center, binormal, width, approach_angle), depth)
- # contact1 = Contact3D(dexnet_model, c1, in_direction=binormal)
- # contact2 = Contact3D(dexnet_model, c2, in_direction=-binormal)
- # print((c2-c1)/np.linalg.norm((c2-c1)), binormal)
- # contacts.append((grasp, contact1, contact2))
dexgrasps.append(grasp)
dexgrasp_list.append(dexgrasps)
@@ -330,15 +296,25 @@ def collision_detection(grasp_list, model_list, dexnet_models, poses, scene_poin
else:
return collision_mask_list, empty_mask_list
-def eval_grasp(grasp_group, models, dexnet_models, poses, config, table=None, voxel_size=0.008):
+def eval_grasp(grasp_group, models, dexnet_models, poses, config, table=None, voxel_size=0.008, TOP_K = 50):
'''
**Input:**
+ - grasp_group: GraspGroup instance for evaluation.
+
- models: in model coordinate
+
+ - dexnet_models: models in dexnet format
- poses: from model to camera coordinate
+
+ - config: dexnet config.
- table: in camera coordinate
+
+ - voxel_size: float of the voxel size.
+
+ - TOP_K: int of the number of top grasps to evaluate.
'''
num_models = len(models)
## grasp nms
@@ -355,16 +331,24 @@ def eval_grasp(grasp_group, models, dexnet_models, poses, config, table=None, vo
seg_mask.append(seg)
seg_mask = np.concatenate(seg_mask, axis=0)
scene = np.concatenate(model_trans_list, axis=0)
- toc = time.time()
# assign grasps
indices = compute_closest_points(grasp_group.translations, scene)
model_to_grasp = seg_mask[indices]
- grasp_list = list()
+ pre_grasp_list = list()
for i in range(num_models):
grasp_i = grasp_group[model_to_grasp==i]
grasp_i.sort_by_score()
- grasp_list.append(grasp_i[:10].grasp_group_array)
+ pre_grasp_list.append(grasp_i[:10].grasp_group_array)
+ all_grasp_list = np.vstack(pre_grasp_list)
+ remain_mask = np.argsort(all_grasp_list[:,0])[::-1]
+ min_score = all_grasp_list[remain_mask[min(49,len(remain_mask) - 1)],0]
+
+ grasp_list = []
+ for i in range(num_models):
+ remain_mask_i = pre_grasp_list[i][:,0] >= min_score
+ grasp_list.append(pre_grasp_list[i][remain_mask_i])
+ # grasp_list = pre_grasp_list
## collision detection
if table is not None:
diff --git a/graspnetAPI/utils/rotation.py b/graspnetAPI/utils/rotation.py
index 499a506..8e69db9 100644
--- a/graspnetAPI/utils/rotation.py
+++ b/graspnetAPI/utils/rotation.py
@@ -1,3 +1,7 @@
+""" Author: chenxi-wang
+ Transformation matrices from/to viewpoints and dexnet gripper params.
+"""
+
import numpy as np
from math import pi
@@ -51,7 +55,7 @@ def matrix_to_dexnet_params(matrix):
R = np.c_[axis_x, np.c_[axis_y, axis_z]]
approach = R.T.dot(approach)
cos_t, sin_t = approach[0], -approach[2]
- angle = np.arccos(cos_t)
+ angle = np.arccos(max(min(cos_t,1),-1))
if sin_t < 0:
angle = pi * 2 - angle
return binormal, angle
@@ -135,4 +139,4 @@ def dexnet_params_to_matrix(binormal, angle):
[-np.sin(angle), 0, np.cos(angle)]])
R2 = np.c_[axis_x, np.c_[axis_y, axis_z]]
matrix = R2.dot(R1)
- return matrix
\ No newline at end of file
+ return matrix
diff --git a/graspnetAPI/utils/utils.py b/graspnetAPI/utils/utils.py
index 4168d0c..fae9f77 100755
--- a/graspnetAPI/utils/utils.py
+++ b/graspnetAPI/utils/utils.py
@@ -8,6 +8,9 @@
from .xmlhandler import xmlReader
class CameraInfo():
+ ''' Author: chenxi-wang
+ Camera intrinsics for point cloud generation.
+ '''
def __init__(self, width, height, fx, fy, cx, cy, scale):
self.width = width
self.height = height
@@ -49,6 +52,23 @@ def create_point_cloud_from_depth_image(depth, camera, organized=True):
return cloud
def generate_views(N, phi=(np.sqrt(5)-1)/2, center=np.zeros(3, dtype=np.float32), R=1):
+ ''' Author: chenxi-wang
+ View sampling on a sphere using Febonacci lattices.
+
+ **Input:**
+
+ - N: int, number of viewpoints.
+
+ - phi: float, constant angle to sample views, usually 0.618.
+
+ - center: numpy array of (3,), sphere center.
+
+ - R: float, sphere radius.
+
+ **Output:**
+
+ - numpy array of (N, 3), coordinates of viewpoints.
+ '''
idxs = np.arange(N, dtype=np.float32)
Z = (2 * idxs + 1) / N - 1
X = np.sqrt(1 - Z**2) * np.cos(2 * idxs * np.pi * phi)
@@ -58,6 +78,27 @@ def generate_views(N, phi=(np.sqrt(5)-1)/2, center=np.zeros(3, dtype=np.float32)
return views
def generate_scene_model(dataset_root, scene_name, anno_idx, return_poses=False, align=False, camera='realsense'):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - dataset_root: str, graspnet dataset root
+
+ - scene_name: str, name of scene folder, e.g. scene_0000
+
+ - anno_idx: int, frame index from 0-255
+
+ - return_poses: bool, return object ids and 6D poses if set to True
+
+ - align: bool, transform to table coordinates if set to True
+
+ - camera: str, camera name (realsense or kinect)
+
+ **Output:**
+
+ - list of open3d.geometry.PointCloud.
+ '''
if align:
camera_poses = np.load(os.path.join(dataset_root, 'scenes', scene_name, camera, 'camera_poses.npy'))
camera_pose = camera_poses[anno_idx]
@@ -92,6 +133,25 @@ def generate_scene_model(dataset_root, scene_name, anno_idx, return_poses=False,
return model_list
def generate_scene_pointcloud(dataset_root, scene_name, anno_idx, align=False, camera='kinect'):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - dataset_root: str, graspnet dataset root
+
+ - scene_name: str, name of scene folder, e.g. scene_0000
+
+ - anno_idx: int, frame index from 0-255
+
+ - align: bool, transform to table coordinates if set to True
+
+ - camera: str, camera name (realsense or kinect)
+
+ **Output:**
+
+ - open3d.geometry.PointCloud.
+ '''
colors = np.array(Image.open(os.path.join(dataset_root, 'scenes', scene_name, camera, 'rgb', '%04d.png'%anno_idx)), dtype=np.float32) / 255.0
depths = np.array(Image.open(os.path.join(dataset_root, 'scenes', scene_name, camera, 'depth', '%04d.png'%anno_idx)))
intrinsics = np.load(os.path.join(dataset_root, 'scenes', scene_name, camera, 'camK.npy'))
@@ -126,6 +186,17 @@ def generate_scene_pointcloud(dataset_root, scene_name, anno_idx, align=False, c
return cloud
def rotation_matrix(rx, ry, rz):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - rx/ry/rz: float, rotation angle along x/y/z-axis
+
+ **Output:**
+
+ - numpy array of (3, 3), rotation matrix.
+ '''
Rx = np.array([[1, 0, 0],
[0, np.cos(rx), -np.sin(rx)],
[0, np.sin(rx), np.cos(rx)]])
@@ -139,6 +210,19 @@ def rotation_matrix(rx, ry, rz):
return R
def transform_matrix(tx, ty, tz, rx, ry, rz):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - tx/ty/tz: float, translation along x/y/z-axis
+
+ - rx/ry/rz: float, rotation angle along x/y/z-axis
+
+ **Output:**
+
+ - numpy array of (4, 4), transformation matrix.
+ '''
trans = np.eye(4)
trans[:3,3] = np.array([tx, ty, tz])
rot_x = np.array([[1, 0, 0],
@@ -154,6 +238,19 @@ def transform_matrix(tx, ty, tz, rx, ry, rz):
return trans
def matrix_to_dexnet_params(matrix):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - numpy array of shape (3, 3) of the rotation matrix.
+
+ **Output:**
+
+ - binormal: numpy array of shape (3,).
+
+ - angle: float of the angle.
+ '''
approach = matrix[:, 0]
binormal = matrix[:, 1]
axis_y = binormal
@@ -172,6 +269,19 @@ def matrix_to_dexnet_params(matrix):
return binormal, angle
def viewpoint_params_to_matrix(towards, angle):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - towards: numpy array towards vector with shape (3,).
+
+ - angle: float of in-plane rotation.
+
+ **Output:**
+
+ - numpy array of the rotation matrix with shape (3, 3).
+ '''
axis_x = towards
axis_y = np.array([-axis_x[1], axis_x[0], 0])
if np.linalg.norm(axis_y) == 0:
@@ -187,6 +297,19 @@ def viewpoint_params_to_matrix(towards, angle):
return matrix
def dexnet_params_to_matrix(binormal, angle):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - binormal: numpy array of shape (3,).
+
+ - angle: float of the angle.
+
+ **Output:**
+
+ - numpy array of shape (3, 3) of the rotation matrix.
+ '''
axis_y = binormal
axis_x = np.array([axis_y[1], -axis_y[0], 0])
if np.linalg.norm(axis_x) == 0:
@@ -202,12 +325,28 @@ def dexnet_params_to_matrix(binormal, angle):
return matrix
def transform_points(points, trans):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - points: numpy array of (N,3), point cloud
+
+ - trans: numpy array of (4,4), transformation matrix
+
+ **Output:**
+
+ - numpy array of (N,3), transformed points.
+ '''
ones = np.ones([points.shape[0],1], dtype=points.dtype)
points_ = np.concatenate([points, ones], axis=-1)
points_ = np.matmul(trans, points_.T).T
return points_[:,:3]
def get_model_grasps(datapath):
+ ''' Author: chenxi-wang
+ Load grasp labels from .npz files.
+ '''
label = np.load(datapath)
points = label['points']
offsets = label['offsets']
@@ -216,6 +355,9 @@ def get_model_grasps(datapath):
return points, offsets, scores, collision
def parse_posevector(posevector):
+ ''' Author: chenxi-wang
+ Decode posevector to object id and transformation matrix.
+ '''
mat = np.zeros([4,4],dtype=np.float32)
alpha, beta, gamma = posevector[4:7]
alpha = alpha / 180.0 * np.pi
@@ -228,6 +370,9 @@ def parse_posevector(posevector):
return obj_idx, mat
def create_mesh_box(width, height, depth, dx=0, dy=0, dz=0):
+ ''' Author: chenxi-wang
+ Create box instance with mesh representation.
+ '''
box = o3d.geometry.TriangleMesh()
vertices = np.array([[0,0,0],
[width,0,0],
@@ -248,6 +393,21 @@ def create_mesh_box(width, height, depth, dx=0, dy=0, dz=0):
return box
def create_table_cloud(width, height, depth, dx=0, dy=0, dz=0, grid_size=0.01):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - width/height/depth: float, table width/height/depth along x/z/y-axis in meters
+
+ - dx/dy/dz: float, offset along x/y/z-axis in meters
+
+ - grid_size: float, point distance along x/y/z-axis in meters
+
+ **Output:**
+
+ - open3d.geometry.PointCloud
+ '''
xmap = np.linspace(0, width, int(width/grid_size))
ymap = np.linspace(0, depth, int(depth/grid_size))
zmap = np.linspace(0, height, int(height/grid_size))
@@ -257,7 +417,6 @@ def create_table_cloud(width, height, depth, dx=0, dy=0, dz=0, grid_size=0.01):
zmap += dz
points = np.stack([xmap, ymap, zmap], axis=-1)
points = points.reshape([-1, 3])
- # print('points',points.shape)
cloud = o3d.geometry.PointCloud()
cloud.points = o3d.utility.Vector3dVector(points)
return cloud
@@ -291,10 +450,23 @@ def plot_axis(R,center,length,grid_size = 0.01):
cloud.points = o3d.utility.Vector3dVector(p)
return cloud
-def plot_gripper_pro_max(center, R, width, depth, score=1):
+def plot_gripper_pro_max(center, R, width, depth, score=1, color=None):
'''
- center: target point
- R: rotation matrix
+ Author: chenxi-wang
+
+ **Input:**
+
+ - center: numpy array of (3,), target point as gripper center
+
+ - R: numpy array of (3,3), rotation matrix of gripper
+
+ - width: float, gripper width
+
+ - score: float, grasp quality score
+
+ **Output:**
+
+ - open3d.geometry.TriangleMesh
'''
x, y, z = center
height=0.004
@@ -302,9 +474,13 @@ def plot_gripper_pro_max(center, R, width, depth, score=1):
tail_length = 0.04
depth_base = 0.02
- color_r = score # red for high score
- color_b = 1 - score # blue for low score
- color_g = 0
+ if color is not None:
+ color_r, color_g, color_b = color
+ else:
+ color_r = score # red for high score
+ color_g = 0
+ color_b = 1 - score # blue for low score
+
left = create_mesh_box(depth+depth_base+finger_width, finger_width, height)
right = create_mesh_box(depth+depth_base+finger_width, finger_width, height)
bottom = create_mesh_box(finger_width, width, height)
@@ -555,7 +731,7 @@ def center_depth(depths, center, open_point, upper_point):
- depth: float of the grasp depth.
'''
- return depths[round(center[1]), round(center[0])]
+ return depths[int(round(center[1])), int(round(center[0]))]
def batch_center_depth(depths, centers, open_points, upper_points):
'''
diff --git a/graspnetAPI/utils/vis.py b/graspnetAPI/utils/vis.py
index d730153..62887f1 100644
--- a/graspnetAPI/utils/vis.py
+++ b/graspnetAPI/utils/vis.py
@@ -7,6 +7,21 @@
from .rotation import viewpoint_params_to_matrix, batch_viewpoint_params_to_matrix
def create_table_cloud(width, height, depth, dx=0, dy=0, dz=0, grid_size=0.01):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - width/height/depth: float, table width/height/depth along x/z/y-axis in meters
+
+ - dx/dy/dz: float, offset along x/y/z-axis in meters
+
+ - grid_size: float, point distance along x/y/z-axis in meters
+
+ **Output:**
+
+ - open3d.geometry.PointCloud
+ '''
xmap = np.linspace(0, width, int(width/grid_size))
ymap = np.linspace(0, depth, int(depth/grid_size))
zmap = np.linspace(0, height, int(height/grid_size))
@@ -43,7 +58,34 @@ def get_camera_parameters(camera='kinect'):
param.intrinsic.set_intrinsics(1280,720,927.17,927.37,639.5,359.5)
return param
-def visAnno(dataset_root, scene_name, anno_idx, camera, num_grasp=10, th=0.3, align_to_table=True, max_width=0.08, save_folder='save_fig', show=False):
+def visAnno(dataset_root, scene_name, anno_idx, camera, num_grasp=10, th=0.3, align_to_table=True, max_width=0.08, save_folder='save_fig', show=False, per_obj=False):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - dataset_root: str, graspnet dataset root
+
+ - scene_name: str, name of scene folder, e.g. scene_0000
+
+ - anno_idx: int, frame index from 0-255
+
+ - camera: str, camera name (realsense or kinect)
+
+ - num_grasp: int, number of sampled grasps
+
+ - th: float, threshold of friction coefficient
+
+ - align_to_table: bool, transform to table coordinates if set to True
+
+ - max_width: float, only visualize grasps with width<=max_width
+
+ - save_folder: str, folder to save screen captures
+
+ - show: bool, show visualization in open3d window if set to True
+
+ - per_obj: bool, show grasps on each object
+ '''
model_list, obj_list, pose_list = generate_scene_model(dataset_root, scene_name, anno_idx, return_poses=True, align=align_to_table, camera=camera)
point_cloud = generate_scene_pointcloud(dataset_root, scene_name, anno_idx, align=align_to_table, camera=camera)
@@ -62,6 +104,7 @@ def visAnno(dataset_root, scene_name, anno_idx, camera, num_grasp=10, th=0.3, al
param.extrinsic = np.linalg.inv(cam_pos).tolist()
grippers = []
+ vis.add_geometry(point_cloud)
for i, (obj_idx, trans) in enumerate(zip(obj_list, pose_list)):
sampled_points, offsets, scores, _ = get_model_grasps('%s/grasp_label/%03d_labels.npz'%(dataset_root, obj_idx))
collision = collision_label['arr_{}'.format(i)]
@@ -106,32 +149,64 @@ def visAnno(dataset_root, scene_name, anno_idx, camera, num_grasp=10, th=0.3, al
if cnt == num_grasp:
break
- vis.add_geometry(point_cloud)
- for gripper in grippers:
- vis.add_geometry(gripper)
- ctr.convert_from_pinhole_camera_parameters(param)
- vis.poll_events()
- filename = os.path.join(save_folder, '{}_{}_pointcloud.png'.format(scene_name, camera))
- if not os.path.exists(save_folder):
- os.mkdir(save_folder)
- vis.capture_screen_image(filename, do_render=True)
- if show:
- o3d.visualization.draw_geometries([point_cloud, *grippers])
+ if per_obj:
+ for gripper in grippers:
+ vis.add_geometry(gripper)
+ ctr.convert_from_pinhole_camera_parameters(param)
+ vis.poll_events()
+ filename = os.path.join(save_folder, '{}_{}_pointcloud_{}.png'.format(scene_name, camera, obj_idx))
+ if not os.path.exists(save_folder):
+ os.mkdir(save_folder)
+ vis.capture_screen_image(filename, do_render=True)
+
+ for gripper in grippers:
+ vis.remove_geometry(gripper)
+ grippers = []
+
+ if not per_obj:
+ for gripper in grippers:
+ vis.add_geometry(gripper)
+ ctr.convert_from_pinhole_camera_parameters(param)
+ vis.poll_events()
+ filename = os.path.join(save_folder, '{}_{}_pointcloud.png'.format(scene_name, camera))
+ if not os.path.exists(save_folder):
+ os.mkdir(save_folder)
+ vis.capture_screen_image(filename, do_render=True)
+ if show:
+ o3d.visualization.draw_geometries([point_cloud, *grippers])
+
+ vis.remove_geometry(point_cloud)
+ vis.add_geometry(table)
+ for model in model_list:
+ vis.add_geometry(model)
+ ctr.convert_from_pinhole_camera_parameters(param)
+ vis.poll_events()
+ filename = os.path.join(save_folder, '{}_{}_model.png'.format(scene_name, camera))
+ vis.capture_screen_image(filename, do_render=True)
+ if show:
+ o3d.visualization.draw_geometries([table, *model_list, *grippers])
+
+
+def vis6D(dataset_root, scene_name, anno_idx, camera, align_to_table=True, save_folder='save_fig', show=False, per_obj=False):
+ '''
+ **Input:**
+ - dataset_root: str, graspnet dataset root
- vis.remove_geometry(point_cloud)
- vis.add_geometry(table)
- for model in model_list:
- vis.add_geometry(model)
- ctr.convert_from_pinhole_camera_parameters(param)
- vis.poll_events()
- filename = os.path.join(save_folder, '{}_{}_model.png'.format(scene_name, camera))
- vis.capture_screen_image(filename, do_render=True)
- if show:
- o3d.visualization.draw_geometries([table, *model_list, *grippers])
+ - scene_name: str, name of scene folder, e.g. scene_0000
+
+ - anno_idx: int, frame index from 0-255
+
+ - camera: str, camera name (realsense or kinect)
+
+ - align_to_table: bool, transform to table coordinates if set to True
+ - save_folder: str, folder to save screen captures
-def vis6D(dataset_root, scene_name, anno_idx, camera, align_to_table=True, save_folder='save_fig', show=False):
+ - show: bool, show visualization in open3d window if set to True
+
+ - per_obj: bool, show pose of each object
+ '''
model_list, obj_list, pose_list = generate_scene_model(dataset_root, scene_name, anno_idx, return_poses=True, align=align_to_table, camera=camera)
point_cloud = generate_scene_pointcloud(dataset_root, scene_name, anno_idx, align=align_to_table, camera=camera)
point_cloud = point_cloud.voxel_down_sample(voxel_size=0.005)
@@ -146,18 +221,46 @@ def vis6D(dataset_root, scene_name, anno_idx, camera, align_to_table=True, save_
param.extrinsic = np.linalg.inv(cam_pos).tolist()
vis.add_geometry(point_cloud)
- for model in model_list:
- vis.add_geometry(model)
- ctr.convert_from_pinhole_camera_parameters(param)
- vis.poll_events()
- filename = os.path.join(save_folder, '{}_{}_6d.png'.format(scene_name, camera))
- vis.capture_screen_image(filename, do_render=True)
- if show:
- o3d.visualization.draw_geometries([point_cloud, *model_list])
+ if per_obj:
+ for i,model in zip(obj_list,model_list):
+ vis.add_geometry(model)
+ ctr.convert_from_pinhole_camera_parameters(param)
+ vis.poll_events()
+ filename = os.path.join(save_folder, '{}_{}_6d_{}.png'.format(scene_name, camera, i))
+ vis.capture_screen_image(filename, do_render=True)
+ vis.remove_geometry(model)
+ else:
+ for model in model_list:
+ vis.add_geometry(model)
+ ctr.convert_from_pinhole_camera_parameters(param)
+ vis.poll_events()
+ filename = os.path.join(save_folder, '{}_{}_6d.png'.format(scene_name, camera))
+ vis.capture_screen_image(filename, do_render=True)
+ if show:
+ o3d.visualization.draw_geometries([point_cloud, *model_list])
+
+
+
+def visObjGrasp(dataset_root, obj_idx, num_grasp=10, th=0.5, max_width=0.08, save_folder='save_fig', show=False):
+ '''
+ Author: chenxi-wang
+
+ **Input:**
+
+ - dataset_root: str, graspnet dataset root
+
+ - obj_idx: int, index of object model
+ - num_grasp: int, number of sampled grasps
+ - th: float, threshold of friction coefficient
-def visObjGrasp(dataset_root, obj_idx, num_grasp=10, th=0.5, save_folder='save_fig', show=False):
+ - max_width: float, only visualize grasps with width<=max_width
+
+ - save_folder: str, folder to save screen captures
+
+ - show: bool, show visualization in open3d window if set to True
+ '''
plyfile = os.path.join(dataset_root, 'models', '%03d'%obj_idx, 'nontextured.ply')
model = o3d.io.read_point_cloud(plyfile)
@@ -198,7 +301,7 @@ def visObjGrasp(dataset_root, obj_idx, num_grasp=10, th=0.5, save_folder='save_f
for d in depth_inds:
if flag: break
angle, depth, width = offset[v, a, d]
- if score[v, a, d] > th or score[v, a, d] < 0:
+ if score[v, a, d] > th or score[v, a, d] < 0 or width > max_width:
continue
R = viewpoint_params_to_matrix(-view, angle)
t = target_point
diff --git a/setup.py b/setup.py
index 50a48ae..d973936 100644
--- a/setup.py
+++ b/setup.py
@@ -5,14 +5,14 @@
setup(
name='graspnetAPI',
- version='1.2.1',
+ version='1.2.11',
description='graspnet API',
author='Hao-Shu Fang, Chenxi Wang, Minghao Gou',
author_email='gouminghao@gmail.com',
url='https://graspnet.net',
packages=find_packages(),
install_requires=[
- 'numpy',
+ 'numpy==1.23.4',
'scipy',
'transforms3d==0.3.1',
'open3d>=0.8.0.0',
@@ -33,4 +33,4 @@
'sklearn',
'grasp_nms'
]
-)
\ No newline at end of file
+)