|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
''' |
|
Visualize the data with both the object mesh and its corresponding grasps, using meshcat. |
|
|
|
Installation: |
|
pip install trimesh==4.5.3 objaverse==0.1.7 meshcat==0.0.12 webdataset==0.2.111 |
|
|
|
Usage: |
|
|
|
Before running the script, start the meshcat server in a different terminal: |
|
meshcat-server |
|
|
|
To visualize a single object from the dataset: |
|
python visualize_dataset.py --dataset_path /path/to/dataset --object_uuid {object_uuid} --object_file /path/to/mesh --gripper_name {choose from: franka, suction, robotiq2f140} |
|
|
|
To visualize many objects (one at a time) from the dataset |
|
python visualize_dataset.py --dataset_path /path/to/dataset --uuid_list /path/to/uuid_list.json --gripper_name {choose from: franka, suction, robotiq2f140} --uuid_object_paths_file /path/to/uuid_object_paths_file.json |
|
|
|
NOTE: |
|
- The uuid_object_paths_file is a json file, that contains a dictionary with a mapping from the UUID to the absolute path of the mesh file. if you are using the download_objaverse.py script, this file will be auto-generated. |
|
- The uuid_list can be the split json file from the GraspGen dataset |
|
- The gripper_name has to be one of the following: franka, suction, robotiq2f140 |
|
''' |
|
|
|
import os |
|
import argparse |
|
import trimesh |
|
import numpy as np |
|
import json |
|
from meshcat_utils import create_visualizer, visualize_mesh, visualize_grasp |
|
from dataset import GraspWebDatasetReader, load_uuid_list |
|
|
|
def visualize_mesh_with_grasps( |
|
mesh_path: str, |
|
mesh_scale: float, |
|
gripper_name: str = "franka", |
|
grasps: list[np.ndarray] = None, |
|
color: list = [192, 192, 192], |
|
transform: np.ndarray = None, |
|
max_grasps_to_visualize: int = 20 |
|
): |
|
""" |
|
Visualize a single mesh with optional grasps using meshcat. |
|
|
|
Args: |
|
mesh_path (str): Path to the mesh file |
|
mesh_scale (float): Scale factor for the mesh |
|
gripper_name (str): Name of the gripper to visualize ("franka", "suction", etc.) |
|
grasps (list[np.ndarray], optional): List of 4x4 grasp transforms |
|
color (list, optional): RGB color for the mesh. Defaults to gray if None |
|
transform (np.ndarray, optional): 4x4 transform matrix for the mesh. Defaults to identity if None |
|
max_grasps_to_visualize (int, optional): Maximum number of grasps to visualize. Defaults to 20 |
|
""" |
|
|
|
vis = create_visualizer() |
|
vis.delete() |
|
|
|
|
|
if transform is None: |
|
transform = np.eye(4) |
|
|
|
|
|
try: |
|
transform = transform.astype(np.float64) |
|
mesh = trimesh.load(mesh_path) |
|
if type(mesh) == trimesh.Scene: |
|
mesh = mesh.dump(concatenate=True) |
|
mesh.apply_scale(mesh_scale) |
|
|
|
T_move_mesh_to_origin = np.eye(4) |
|
T_move_mesh_to_origin[:3, 3] = -mesh.centroid |
|
|
|
transform = transform @ T_move_mesh_to_origin |
|
|
|
visualize_mesh(vis, 'mesh', mesh, color=color, transform=transform) |
|
except Exception as e: |
|
print(f"Error loading mesh from {mesh_path}: {e}") |
|
|
|
|
|
if grasps is not None: |
|
for i, grasp in enumerate(np.random.permutation(grasps)[:max_grasps_to_visualize]): |
|
visualize_grasp( |
|
vis, |
|
f"grasps/{i:03d}", |
|
transform @ grasp.astype(np.float), |
|
[0, 255, 0], |
|
gripper_name=gripper_name, |
|
linewidth=0.2 |
|
) |
|
|
|
|
|
def parse_args(): |
|
parser = argparse.ArgumentParser() |
|
parser.add_argument("--dataset_path", type=str, required=True) |
|
parser.add_argument("--object_uuid", type=str, help="The UUID of the object to visualize", default=None) |
|
parser.add_argument("--uuid_list", type=str, help="Path to UUID list", default=None) |
|
parser.add_argument("--uuid_object_paths_file", type=str, help="Path to JSON file, mapping UUID to absolute path of the mesh file", default=None) |
|
parser.add_argument("--object_file", type=str, help="This has to be a .stl or .obj or .glb file", default=None) |
|
parser.add_argument("--gripper_name", type=str, required=True, help="Specify the gripper name", choices=["franka", "suction", "robotiq2f140"]) |
|
parser.add_argument("--max_grasps_to_visualize", type=int, help="The max number of grasps to visualize", default=20) |
|
return parser.parse_args() |
|
|
|
if __name__ == "__main__": |
|
args = parse_args() |
|
assert args.object_uuid is not None or args.uuid_list is not None, "Either object_uuid or uuid_list must be provided" |
|
|
|
if args.object_uuid is not None: |
|
webdataset_reader = GraspWebDatasetReader(os.path.join(args.dataset_path, args.gripper_name)) |
|
uuid_list = [args.object_uuid,] |
|
object_paths = [args.object_file,] |
|
assert args.object_file is not None, "object_file must be provided if object_uuid is provided" |
|
assert os.path.exists(args.object_file), f"Object file {args.object_file} does not exist" |
|
else: |
|
assert os.path.exists(args.uuid_list), f"UUID list {args.uuid_list} does not exist" |
|
uuid_list = load_uuid_list(args.uuid_list) |
|
assert args.uuid_object_paths_file is not None, "uuid_object_paths_file must be provided if uuid_list is provided" |
|
assert os.path.exists(args.uuid_object_paths_file), f"UUID object paths file {args.uuid_object_paths_file} does not exist" |
|
object_paths = json.load(open(args.uuid_object_paths_file)) |
|
object_paths = [object_paths[uuid] for uuid in uuid_list] |
|
webdataset_reader = GraspWebDatasetReader(os.path.join(args.dataset_path, args.gripper_name)) |
|
|
|
for uuid, object_path in zip(uuid_list, object_paths): |
|
print(f"Visualizing object {uuid}") |
|
grasp_data = webdataset_reader.read_grasps_by_uuid(uuid) |
|
object_scale = grasp_data['object']['scale'] |
|
grasps = grasp_data["grasps"] |
|
grasp_poses = np.array(grasps["transforms"]) |
|
grasp_mask = np.array(grasps["object_in_gripper"]) |
|
positive_grasps = grasp_poses[grasp_mask] |
|
|
|
if len(positive_grasps) > 0: |
|
|
|
visualize_mesh_with_grasps( |
|
mesh_path=object_path, |
|
mesh_scale=object_scale, |
|
grasps=positive_grasps, |
|
gripper_name=args.gripper_name, |
|
max_grasps_to_visualize=args.max_grasps_to_visualize, |
|
) |
|
print("Press Enter to continue...") |
|
input() |