-
Notifications
You must be signed in to change notification settings - Fork 11
/
Copy pathevaluate_generator.py
149 lines (139 loc) · 6.06 KB
/
evaluate_generator.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
from argparse import ArgumentParser
from environment import GraspSimulationEnv
from distribute import Pool
from utils import dicts_get, load_config, load_evaluate_config
from learning import ObjectDataset
import numpy as np
import ray
import os
from tqdm import tqdm
from learning.finger_generator import get_finger_generator, ImprintFingerGenerator
from shutil import copyfile
from os.path import splitext
from json import dump
import pickle
def acc_results(results):
metrics = {
'base_connected': np.empty(0),
'created_grippers_failed': np.empty(0),
'single_connected_component': np.empty(0),
'grasp_object_path': []
}
for key in results[0]['score'].keys():
metrics[key] = np.empty(0)
for r in results:
if r["score"] is None:
print("Score is none. Ignoring ...")
continue
metrics['base_connected'] = np.concatenate(
(metrics['base_connected'],
[r['base_connected']]))
metrics['created_grippers_failed'] = np.concatenate(
(metrics['created_grippers_failed'],
[r['created_grippers_failed']]))
metrics['single_connected_component'] = np.concatenate(
(metrics["single_connected_component"],
[r["single_connected_component"]]))
metrics['grasp_object_path'].append(r['grasp_object_path'])
for key, r_val in r["score"].items():
metrics[key] = np.concatenate((metrics[key], [r_val]))
for key, val in metrics.items():
if key is not 'grasp_object_path':
metrics[key] = metrics[key].astype(float)
return metrics
def print_results(metrics, name=""):
print(f"Results summary {name}:")
for key, val in metrics.items():
if key != 'grasp_object_path':
print(f"{key}: {np.mean(np.array(val, dtype=float)):.4f}")
if __name__ == '__main__':
parser = ArgumentParser('Generator fingers evaluater')
parser.add_argument("--evaluate_config",
help="path to evaluate config file",
required=True,
type=str)
parser.add_argument('--objects',
help='path to shapenet root',
type=str,
required=True)
parser.add_argument('--config',
help='path to JSON config file',
type=str,
default='configs/default.json')
parser.add_argument('--name',
help='path to directory to save results',
type=str, required=True)
parser.add_argument('--num_processes',
help='number of environment processes',
type=int,
default=32)
parser.add_argument('--gui', action='store_true',
default=False, help='Run headless or render')
parser.add_argument('--objects_bs',
help='objects batch size',
type=int,
default=128)
args = parser.parse_args()
# load environment
ray.init()
config = load_config(args.config)
env_pool = Pool([GraspSimulationEnv.remote(
config=config,
gui=args.gui
) for _ in range(args.num_processes)])
# object dataset
obj_dataset = ObjectDataset(
directory_path=args.objects,
batch_size=args.objects_bs,
)
grippers_directory = args.name + '/'
assert not os.path.exists(grippers_directory)
os.makedirs(grippers_directory)
# evaluations
evaluate_config = load_evaluate_config(args.evaluate_config)
# dump config and args
print("logging to ", grippers_directory)
dump(config, open(grippers_directory + 'config.json', 'w'), indent=4)
dump(evaluate_config, open(grippers_directory + 'evaluate_config.json', 'w'), indent=4)
pickle.dump(args,open(grippers_directory + 'args.pkl','wb'))
finger_generators = []
for finger_generator_config in evaluate_config:
if not finger_generator_config["evaluate"]: # TODO: Do it more neatly
continue
results = []
finger_generator = get_finger_generator(finger_generator_config)
print(finger_generator)
obj_loader = iter(obj_dataset.loader)
for i, grasp_objects in enumerate(tqdm(obj_loader, smoothing=0.01, dynamic_ncols=True, desc=finger_generator_config["desc"])):
retval = finger_generator.create_fingers(
grasp_objects)
gripper_output_paths = ['{}/{:06}'.format(
grippers_directory, i + len(results))
for i in range(len(grasp_objects))]
if type(finger_generator) == ImprintFingerGenerator:
left_fingers, right_fingers, gripper_urdf_paths = retval
for gripper_urdf_path, target_gripper_urdf_path in \
zip(gripper_urdf_paths, gripper_output_paths):
# copy collision meshes over
prefix = splitext(gripper_urdf_path)[0]
copyfile(prefix + '_right_collision.obj',
target_gripper_urdf_path + '_right_collision.obj')
copyfile(prefix + '_left_collision.obj',
target_gripper_urdf_path + '_left_collision.obj')
else:
left_fingers, right_fingers = retval
grasp_results = env_pool.map(
exec_fn=lambda env, args:
env.compute_finger_grasp_score.remote(*args),
iterable=zip(
left_fingers,
right_fingers,
dicts_get(grasp_objects, 'urdf_path'),
gripper_output_paths,
[False] * len(gripper_output_paths)))
results.extend(grasp_results)
metrics = acc_results(results)
print_results(metrics, name=finger_generator_config["desc"])
save_path = os.path.join(grippers_directory, "val_results.npz")
np.savez(save_path, **metrics)
print(f"saved results at {save_path}")