graspnetAPI.utils package¶
Subpackages¶
- graspnetAPI.utils.dexnet package
- Subpackages
- graspnetAPI.utils.dexnet.grasping package
- Subpackages
- Submodules
- graspnetAPI.utils.dexnet.grasping.contacts module
- graspnetAPI.utils.dexnet.grasping.grasp module
- graspnetAPI.utils.dexnet.grasping.grasp_quality_config module
- graspnetAPI.utils.dexnet.grasping.grasp_quality_function module
- graspnetAPI.utils.dexnet.grasping.graspable_object module
- graspnetAPI.utils.dexnet.grasping.quality module
- Module contents
- graspnetAPI.utils.dexnet.grasping package
- Submodules
- graspnetAPI.utils.dexnet.abstractstatic module
- graspnetAPI.utils.dexnet.constants module
- Module contents
- Subpackages
Submodules¶
graspnetAPI.utils.config module¶
graspnetAPI.utils.eval_utils module¶
-
graspnetAPI.utils.eval_utils.
collision_detection
(grasp_list, model_list, dexnet_models, poses, scene_points, outlier=0.05, empty_thresh=10, return_dexgrasps=False)[source]¶ Input:
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 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,)]
dexgrasp_list: [[ParallelJawPtGrasp3D,],] in object coordinate
-
graspnetAPI.utils.eval_utils.
compute_closest_points
(A, B)[source]¶ Input:
A: (N, 3)
B: (M, 3)
Output:
indices: (N,) closest point index in B for each point in A
-
graspnetAPI.utils.eval_utils.
compute_point_distance
(A, B)[source]¶ Input: - A: (N, 3)
B: (M, 3)
Output: - dists: (N, M)
-
graspnetAPI.utils.eval_utils.
create_table_points
(lx, ly, lz, dx=0, dy=0, dz=0, grid_size=0.01)[source]¶ Input: - lx: - ly: - lz: Output: - numpy array of the points with shape (-1, 3).
-
graspnetAPI.utils.eval_utils.
eval_grasp
(grasp_group, models, dexnet_models, poses, config, table=None, voxel_size=0.008, TOP_K=50)[source]¶ 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.
-
graspnetAPI.utils.eval_utils.
get_grasp_score
(grasp, obj, fc_list, force_closure_quality_config)[source]¶
-
graspnetAPI.utils.eval_utils.
get_scene_name
(num)[source]¶ Input: - num: int of the scene number.
Output: - string of the scene name.
-
graspnetAPI.utils.eval_utils.
load_dexnet_model
(data_path)[source]¶ Input:
data_path: path to load .obj & .sdf files
Output: - obj: dexnet model
-
graspnetAPI.utils.eval_utils.
parse_posevector
(posevector)[source]¶ 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.
-
graspnetAPI.utils.eval_utils.
topk_grasps
(grasps, k=10)[source]¶ Input:
grasps: (N, 17)
k: int
Output:
topk_grasps: (k, 17)
graspnetAPI.utils.pose module¶
-
class
graspnetAPI.utils.pose.
Pose
(id, x, y, z, alpha, beta, gamma)[source]¶ Bases:
object
graspnetAPI.utils.rotation module¶
Author: chenxi-wang Transformation matrices from/to viewpoints and dexnet gripper params.
-
graspnetAPI.utils.rotation.
batch_viewpoint_params_to_matrix
(batch_towards, batch_angle)[source]¶ Input:
towards: numpy array towards vectors with shape (n, 3).
angle: numpy array of in-plane rotations (n, ).
Output:
numpy array of the rotation matrix with shape (n, 3, 3).
-
graspnetAPI.utils.rotation.
dexnet_params_to_matrix
(binormal, angle)[source]¶ Input:
binormal: numpy array of shape (3,).
angle: float of the angle.
Output:
numpy array of shape (3, 3) of the rotation matrix.
-
graspnetAPI.utils.rotation.
matrix_to_dexnet_params
(matrix)[source]¶ Input:
numpy array of shape (3, 3) of the rotation matrix.
Output:
binormal: numpy array of shape (3,).
angle: float of the angle.
graspnetAPI.utils.trans3d module¶
-
graspnetAPI.utils.trans3d.
get_mat
(x, y, z, alpha, beta, gamma)[source]¶ Calls get_mat() to get the 4x4 matrix
graspnetAPI.utils.utils module¶
-
class
graspnetAPI.utils.utils.
CameraInfo
(width, height, fx, fy, cx, cy, scale)[source]¶ Bases:
object
Author: chenxi-wang Camera intrinsics for point cloud generation.
-
graspnetAPI.utils.utils.
batch_center_depth
(depths, centers, open_points, upper_points)[source]¶ Input:
depths: numpy array of the depths.
centers: numpy array of the center points of shape(-1, 2).
open_points: numpy array of the open points of shape(-1, 2).
upper_points: numpy array of the upper points of shape(-1, 2).
Output:
depths: numpy array of the grasp depth of shape (-1).
-
graspnetAPI.utils.utils.
batch_framexy_depth_2_xyz
(pixel_x, pixel_y, depth, camera)[source]¶ Input:
pixel_x: numpy array of int of the pixel x coordinate. shape: (-1,)
pixel_y: numpy array of int of the pixle y coordicate. shape: (-1,)
depth: numpy array of float of depth. The unit is millimeter. shape: (-1,)
camera: string of type of camera. “realsense” or “kinect”.
Output:
x, y, z: numpy array of float of x, y and z coordinates in camera frame. The unit is millimeter.
-
graspnetAPI.utils.utils.
batch_key_point_2_rotation
(centers_xyz, open_points_xyz, upper_points_xyz)[source]¶ Input:
centers_xyz: numpy array of the center points of shape (-1, 3).
open_points_xyz: numpy array of the open points of shape (-1, 3).
upper_points_xyz: numpy array of the upper points of shape (-1, 3).
Output:
rotations: numpy array of the rotation matrix of shape (-1, 3, 3).
-
graspnetAPI.utils.utils.
batch_key_points_2_tuple
(key_points, scores, object_ids, camera)[source]¶ Input:
key_points: np.array(-1,4,3) of grasp key points, definition is shown in key_points.png
scores: numpy array of batch grasp scores.
camera: string of ‘realsense’ or ‘kinect’.
Output:
np.array([center_x,center_y,open_x,open_y,height])
-
graspnetAPI.utils.utils.
batch_rgbdxyz_2_rgbxy_depth
(points, camera)[source]¶ Input:
points: np.array(-1,3) of the points in camera frame
camera: string of the camera type
Output:
coords: float of xy in pixel frame [-1, 2]
depths: float of the depths of pixel frame [-1]
-
graspnetAPI.utils.utils.
center_depth
(depths, center, open_point, upper_point)[source]¶ Input:
depths: numpy array of the depths.
center: numpy array of the center point.
open_point: numpy array of the open point.
upper_point: numpy array of the upper point.
Output:
depth: float of the grasp depth.
-
graspnetAPI.utils.utils.
create_mesh_box
(width, height, depth, dx=0, dy=0, dz=0)[source]¶ Author: chenxi-wang Create box instance with mesh representation.
-
graspnetAPI.utils.utils.
create_table_cloud
(width, height, depth, dx=0, dy=0, dz=0, grid_size=0.01)[source]¶ 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
-
graspnetAPI.utils.utils.
dexnet_params_to_matrix
(binormal, angle)[source]¶ 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.
-
graspnetAPI.utils.utils.
framexy_depth_2_xyz
(pixel_x, pixel_y, depth, camera)[source]¶ Input:
pixel_x: int of the pixel x coordinate.
pixel_y: int of the pixle y coordicate.
depth: float of depth. The unit is millimeter.
camera: string of type of camera. “realsense” or “kinect”.
Output:
x, y, z: float of x, y and z coordinates in camera frame. The unit is millimeter.
-
graspnetAPI.utils.utils.
generate_scene
(scene_idx, anno_idx, return_poses=False, align=False, camera='realsense')[source]¶
-
graspnetAPI.utils.utils.
generate_scene_model
(dataset_root, scene_name, anno_idx, return_poses=False, align=False, camera='realsense')[source]¶ 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.
-
graspnetAPI.utils.utils.
generate_scene_pointcloud
(dataset_root, scene_name, anno_idx, align=False, camera='kinect')[source]¶ 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.
-
graspnetAPI.utils.utils.
generate_views
(N, phi=0.6180339887498949, center=array([0.0, 0.0, 0.0], dtype=float32), R=1)[source]¶ 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.
-
graspnetAPI.utils.utils.
get_batch_key_points
(centers, Rs, widths)[source]¶ Input:
centers: np.array(-1,3) of the translation
Rs: np.array(-1,3,3) of the rotation matrix
widths: np.array(-1) of the grasp width
Output:
key_points: np.array(-1,4,3) of the key point of the grasp
-
graspnetAPI.utils.utils.
get_camera_intrinsic
(camera)[source]¶ Input:
camera: string of type of camera, “realsense” or “kinect”.
Output:
numpy array of shape (3, 3) of the camera intrinsic matrix.
-
graspnetAPI.utils.utils.
get_model_grasps
(datapath)[source]¶ Author: chenxi-wang Load grasp labels from .npz files.
-
graspnetAPI.utils.utils.
key_point_2_rotation
(center_xyz, open_point_xyz, upper_point_xyz)[source]¶ Input:
center_xyz: numpy array of the center point.
open_point_xyz: numpy array of the open point.
upper_point_xyz: numpy array of the upper point.
Output:
rotation: numpy array of the rotation matrix.
-
graspnetAPI.utils.utils.
matrix_to_dexnet_params
(matrix)[source]¶ 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.
-
graspnetAPI.utils.utils.
parse_posevector
(posevector)[source]¶ Author: chenxi-wang Decode posevector to object id and transformation matrix.
-
graspnetAPI.utils.utils.
plot_gripper_pro_max
(center, R, width, depth, score=1, color=None)[source]¶ 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
-
graspnetAPI.utils.utils.
rotation_matrix
(rx, ry, rz)[source]¶ Author: chenxi-wang
Input:
rx/ry/rz: float, rotation angle along x/y/z-axis
Output:
numpy array of (3, 3), rotation matrix.
-
graspnetAPI.utils.utils.
transform_matrix
(tx, ty, tz, rx, ry, rz)[source]¶ 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.
graspnetAPI.utils.vis module¶
-
graspnetAPI.utils.vis.
create_table_cloud
(width, height, depth, dx=0, dy=0, dz=0, grid_size=0.01)[source]¶ 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
-
graspnetAPI.utils.vis.
get_camera_parameters
(camera='kinect')[source]¶ author: Minghao Gou
Input:
camera: string of type of camera: ‘kinect’ or ‘realsense’
Output:
open3d.camera.PinholeCameraParameters
-
graspnetAPI.utils.vis.
vis6D
(dataset_root, scene_name, anno_idx, camera, align_to_table=True, save_folder='save_fig', show=False, per_obj=False)[source]¶ 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)
align_to_table: bool, transform to table coordinates if set to True
save_folder: str, folder to save screen captures
show: bool, show visualization in open3d window if set to True
per_obj: bool, show pose of each object
-
graspnetAPI.utils.vis.
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)[source]¶ 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
-
graspnetAPI.utils.vis.
visObjGrasp
(dataset_root, obj_idx, num_grasp=10, th=0.5, max_width=0.08, save_folder='save_fig', show=False)[source]¶ 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
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
-
graspnetAPI.utils.vis.
vis_rec_grasp
(rec_grasp_tuples, numGrasp, image_path, save_path, show=False)[source]¶ author: Minghao Gou
Input:
rec_grasp_tuples: np.array of rectangle grasps
numGrasp: int of total grasps number to show
image_path: string of path of the image
image_path: string of the path to save the image
show: bool of whether to show the image
Output:
no output but display the rectangle grasps in image
graspnetAPI.utils.xmlhandler module¶
-
graspnetAPI.utils.xmlhandler.
getframeposevectorlist
(objectidlist, is_resume, frame_number, xml_dir)[source]¶
-
graspnetAPI.utils.xmlhandler.
getposevectorlist
(objectidlist, is_resume, num_frame, frame_number, xml_dir)[source]¶