graspnetAPI package

Subpackages

Submodules

graspnetAPI.grasp module

class graspnetAPI.grasp.Grasp(*args)[source]

Bases: object

property depth

Output:

  • float of the depth.

property height

Output:

  • float of the height.

property object_id

Output:

  • int of the object id that this grasp grasps

property rotation_matrix

Output:

  • np.array of shape (3, 3) of the rotation matrix.

property score

Output:

  • float of the score.

to_open3d_geometry(color=None)[source]

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.

transform(T)[source]

Input:

  • T: np.array of shape (4, 4)

Output:

  • Grasp instance after transformation, the original Grasp will also be changed.

property translation

Output:

  • np.array of shape (3,) of the translation.

property width

Output:

  • float of the width.

class graspnetAPI.grasp.GraspGroup(*args)[source]

Bases: object

add(element)[source]

Input:

  • element: Grasp instance or GraspGroup instance.

property depths

Output:

  • numpy array of shape (-1, ) of the depths.

from_npy(npy_file_path)[source]

Input:

  • npy_file_path: string of the file path.

property heights

Output:

  • numpy array of shape (-1, ) of the heights.

nms(translation_thresh=0.03, rotation_thresh=0.5235987755982988)[source]

Input:

  • translation_thresh: float of the translation threshold.

  • rotation_thresh: float of the rotation threshold.

Output:

  • GraspGroup instance after nms.

property object_ids

Output:

  • numpy array of shape (-1, ) of the object ids.

random_sample(numGrasp=20)[source]

Input:

  • numGrasp: int of the number of sampled grasps.

Output:

  • GraspGroup instance of sample grasps.

remove(index)[source]

Input:

  • index: list of the index of grasp

property rotation_matrices

Output:

  • np.array of shape (-1, 3, 3) of the rotation matrices.

save_npy(npy_file_path)[source]

Input:

  • npy_file_path: string of the file path.

property scores

Output:

  • numpy array of shape (-1, ) of the scores.

sort_by_score(reverse=False)[source]

Input:

  • reverse: bool of order, if False, from high to low, if True, from low to high.

Output:

  • no output but sort the grasp group.

to_open3d_geometry_list()[source]

Output:

  • list of open3d.geometry.Geometry of the grippers.

to_rect_grasp_group(camera)[source]

Input:

  • camera: string of type of camera, ‘realsense’ or ‘kinect’.

Output:

  • RectGraspGroup instance or None.

transform(T)[source]

Input:

  • T: np.array of shape (4, 4)

Output:

  • GraspGroup instance after transformation, the original GraspGroup will also be changed.

property translations

Output:

  • np.array of shape (-1, 3) of the translations.

property widths

Output:

  • numpy array of shape (-1, ) of the widths.

class graspnetAPI.grasp.RectGrasp(*args)[source]

Bases: object

property center_point

Output:

  • tuple of x,y of the center point.

get_key_points()[source]

Output:

  • center, open_point, upper_point, each of them is a numpy array of shape (2,)

property height

Output:

  • float of the height.

property object_id

Output:

  • int of the object id that this grasp grasps

property open_point

Output:

  • tuple of x,y of the open point.

property score

Output:

  • float of the score.

to_grasp(camera, depths, depth_method=<function center_depth>)[source]

Input:

  • camera: string of type of camera, ‘kinect’ or ‘realsense’.

  • depths: numpy array of the depths image.

  • depth_method: function of calculating the depth.

Output:

  • grasp: Grasp instance of None if the depth is not valid.

to_opencv_image(opencv_rgb)[source]

input:

  • opencv_rgb: numpy array of opencv BGR format.

Output:

  • numpy array of opencv RGB format that shows the rectangle grasp.

class graspnetAPI.grasp.RectGraspGroup(*args)[source]

Bases: object

add(rect_grasp)[source]

Input:

  • rect_grasp: RectGrasp instance

batch_get_key_points()[source]

Output:

  • center, open_point, upper_point, each of them is a numpy array of shape (2,)

property center_points

Output:

  • numpy array the center points of shape (-1, 2).

from_npy(npy_file_path)[source]

Input:

  • npy_file_path: string of the file path.

property heights

Output:

  • numpy array of the heights.

property object_ids

Output:

  • numpy array of the object ids that this grasp grasps.

property open_points

Output:

  • numpy array the open points of shape (-1, 2).

random_sample(numGrasp=20)[source]

Input:

  • numGrasp: int of the number of sampled grasps.

Output:

  • RectGraspGroup instance of sample grasps.

remove(index)[source]

Input:

  • index: list of the index of rect_grasp

save_npy(npy_file_path)[source]

Input:

  • npy_file_path: string of the file path.

property scores

Output:

  • numpy array of the scores.

sort_by_score(reverse=False)[source]

Input:

  • reverse: bool of order, if False, from high to low, if True, from low to high.

Output:

  • no output but sort the grasp group.

to_grasp_group(camera, depths, depth_method=<function batch_center_depth>)[source]

Input:

  • camera: string of type of camera, ‘kinect’ or ‘realsense’.

  • depths: numpy array of the depths image.

  • depth_method: function of calculating the depth.

Output:

  • grasp_group: GraspGroup instance or None.

Note

The number may not be the same to the input as some depth may be invalid.

to_opencv_image(opencv_rgb, numGrasp=0)[source]

input:

  • opencv_rgb: numpy array of opencv BGR format.

  • numGrasp: int of the number of grasp, 0 for all.

Output:

  • numpy array of opencv RGB format that shows the rectangle grasps.

graspnetAPI.graspnet module

class graspnetAPI.graspnet.GraspNet(root, camera='kinect', split='train')[source]

Bases: object

checkDataCompleteness()[source]

Check whether the dataset files are complete.

Output:

  • bool, True for complete, False for not complete.

getDataIds(sceneIds=None)[source]

Input:

  • sceneIds:int or list of int of the scenes ids.

Output:

  • a list of int of the data ids. Data could be accessed by calling self.loadData(ids).

getObjIds(sceneIds=None)[source]

Input:

  • sceneIds: int or list of int of the scene ids.

Output:

  • a list of int of the object ids in the given scenes.

getSceneIds(objIds=None)[source]

Input:

  • objIds: int or list of int of the object ids.

Output:

  • a list of int of the scene ids that contains all the objects.

loadBGR(sceneId, camera, annId)[source]

Input:

  • sceneId: int of the scene index.

  • camera: string of type of camera, ‘realsense’ or ‘kinect’

  • annId: int of the annotation index.

Output:

  • numpy array of the rgb in BGR order.

loadCollisionLabels(sceneIds=None)[source]

Input:

  • sceneIds: int or list of int of the scene ids.

Output:

  • dict of the collision labels.

loadData(ids=None, *extargs)[source]

Input:

  • ids: int or list of int of the the data ids.

  • extargs: extra arguments. This function can also be called with loadData(sceneId, camera, annId)

Output:

  • if ids is int, returns a tuple of data path

  • if ids is not specified or is a list, returns a tuple of data path lists

loadDepth(sceneId, camera, annId)[source]

Input:

  • sceneId: int of the scene index.

  • camera: string of type of camera, ‘realsense’ or ‘kinect’

  • annId: int of the annotation index.

Output:

  • numpy array of the depth with dtype = np.uint16

loadGrasp(sceneId, annId=0, format='6d', camera='kinect', grasp_labels=None, collision_labels=None, fric_coef_thresh=0.4)[source]

Input:

  • sceneId: int of scene id.

  • annId: int of annotation id.

  • format: string of grasp format, ‘6d’ or ‘rect’.

  • camera: string of camera type, ‘kinect’ or ‘realsense’.

  • grasp_labels: dict of grasp labels. Call self.loadGraspLabels if not given.

  • collision_labels: dict of collision labels. Call self.loadCollisionLabels if not given.

  • fric_coef_thresh: float of the frcition coefficient threshold of the grasp.

ATTENTION

the LOWER the friction coefficient is, the better the grasp is.

Output:

  • If format == ‘6d’, return a GraspGroup instance.

  • If format == ‘rect’, return a RectGraspGroup instance.

loadGraspLabels(objIds=None)[source]

Input:

  • objIds: int or list of int of the object ids.

Output:

  • a dict of grasplabels of each object.

loadMask(sceneId, camera, annId)[source]

Input:

  • sceneId: int of the scene index.

  • camera: string of type of camera, ‘realsense’ or ‘kinect’

  • annId: int of the annotation index.

Output:

  • numpy array of the mask with dtype = np.uint16

loadObjModels(objIds=None)[source]

Function:

  • load object 3D models of the given obj ids

Input:

  • objIDs: int or list of int of the object ids

Output:

  • a list of open3d.geometry.PointCloud of the models

loadObjTrimesh(objIds=None)[source]

Function:

  • load object 3D trimesh of the given obj ids

Input:

  • objIDs: int or list of int of the object ids

Output:

  • a list of trimesh.Trimesh of the models

loadRGB(sceneId, camera, annId)[source]

Input:

  • sceneId: int of the scene index.

  • camera: string of type of camera, ‘realsense’ or ‘kinect’

  • annId: int of the annotation index.

Output:

  • numpy array of the rgb in RGB order.

loadSceneModel(sceneId, camera='kinect', annId=0, align=False)[source]

Input:

  • sceneId: int of the scene index.

  • camera: string of type of camera, ‘realsense’ or ‘kinect’

  • annId: int of the annotation index.

  • align: bool of whether align to the table frame.

Output:

  • open3d.geometry.PointCloud list of the scene models.

loadScenePointCloud(sceneId, camera, annId, align=False, format='open3d', use_workspace=False, use_mask=True, use_inpainting=False)[source]

Input:

  • sceneId: int of the scene index.

  • camera: string of type of camera, ‘realsense’ or ‘kinect’

  • annId: int of the annotation index.

  • aligh: bool of whether align to the table frame.

  • format: string of the returned type. ‘open3d’ or ‘numpy’

  • 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:

  • open3d.geometry.PointCloud instance of the scene point cloud.

  • or tuple of numpy array of point locations and colors.

loadWorkSpace(sceneId, camera, annId)[source]

Input:

  • sceneId: int of the scene index.

  • camera: string of type of camera, ‘realsense’ or ‘kinect’

  • annId: int of the annotation index.

Output:

  • tuple of the bounding box coordinates (x1, y1, x2, y2).

show6DPose(sceneIds, saveFolder='save_fig', show=False, perObj=False)[source]

Input:

  • sceneIds: int or list of scene ids.

  • saveFolder: string of the folder to store the image.

  • 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.

showObjGrasp(objIds=[], numGrasp=10, th=0.5, maxWidth=0.08, saveFolder='save_fig', show=False)[source]

Input:

  • objIds: int of list of objects ids.

  • numGrasp: how many grasps to show in the image.

  • 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.

Output:

  • No output but save the rendered image and maybe show it.

showSceneGrasp(sceneId, camera='kinect', annId=0, format='6d', numGrasp=20, show_object=True, coef_fric_thresh=0.1)[source]

Input:

  • sceneId: int of the scene index.

  • camera: string of the camera type, ‘realsense’ or ‘kinect’.

  • annId: int of the annotation index.

  • format: int of the annotation type, ‘rect’ or ‘6d’.

  • numGrasp: int of the displayed grasp number, grasps will be randomly sampled.

  • coef_fric_thresh: float of the friction coefficient of grasps.

graspnetAPI.graspnet_eval module

class graspnetAPI.graspnet_eval.GraspNetEval(root, camera, split='test')[source]

Bases: graspnetAPI.graspnet.GraspNet

Class for evaluation on GraspNet dataset.

Input:

  • root: string of root path for the dataset.

  • camera: string of type of the camera.

  • split: string of the date split.

eval_all(dump_folder, proc=2)[source]

Input:

  • dump_folder: string of the folder that saves the npy files.

  • proc: int of the number of processes to use to evaluate.

Output:

  • res: numpy array of the detailed accuracy.

  • ap: float of the AP for all split.

eval_novel(dump_folder, proc=2)[source]

Input:

  • dump_folder: string of the folder that saves the npy files.

  • proc: int of the number of processes to use to evaluate.

Output:

  • res: numpy array of the detailed accuracy.

  • ap: float of the AP for novel split.

eval_scene(scene_id, dump_folder, TOP_K=50, return_list=False, vis=False, max_width=0.1)[source]

Input:

  • scene_id: int of the scene index.

  • 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.

eval_seen(dump_folder, proc=2)[source]

Input:

  • dump_folder: string of the folder that saves the npy files.

  • proc: int of the number of processes to use to evaluate.

Output:

  • res: numpy array of the detailed accuracy.

  • ap: float of the AP for seen split.

eval_similar(dump_folder, proc=2)[source]

Input:

  • dump_folder: string of the folder that saves the npy files.

  • proc: int of the number of processes to use to evaluate.

Output:

  • res: numpy array of the detailed accuracy.

  • ap: float of the AP for similar split.

get_model_poses(scene_id, ann_id)[source]

Input:

  • scene_id: int of the scen index.

  • ann_id: int of the annotation index.

Output:

  • obj_list: list of int of object index.

  • pose_list: list of 4x4 matrices of object poses.

  • camera_pose: 4x4 matrix of the camera pose relative to the first frame.

  • align mat: 4x4 matrix of camera relative to the table.

get_scene_models(scene_id, ann_id)[source]

return models in model coordinate

parallel_eval_scenes(scene_ids, dump_folder, proc=2)[source]

Input:

  • scene_ids: list of int of scene index.

  • dump_folder: string of the folder that saves the npy files.

  • proc: int of the number of processes to use to evaluate.

Output:

  • scene_acc_list: list of the scene accuracy.

Module contents