-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathbenchmarking.py
114 lines (97 loc) · 5.32 KB
/
benchmarking.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
import os
import sys
DIR = os.path.dirname(os.path.realpath(__file__))
sys.path.append(DIR)
from src.world import BlenderWorld
from src.sampling import *
from src import pybullet_simulation
from src import robowflex_simulation
from src import calc
# output settings and world properties
world_config = {
"dir_for_output": "../benchmarking/v0", # both absolute and relative paths are allowed
"link_size_reduction": 0.001, # reduce the size of every link by this value to avoid touching and
# permanent collision
"export_entity_srdf": True,
"absolute_path_for_meshes_in_urdf": True, # generate an absolute path to reference the output meshes from within
# the urdf if True, else use a relative path
"export_mesh_dae": False,
"export_mesh_stl": True,
"output_mesh_type": 'stl',
}
sampler_config = {
# this part of the config is always required
"floor_size": 32,
"number_prismatic_joints": 0,
"number_revolute_joints": 0,
"branching_factor_target": 2, # should not be higher than number_revolute_joints
"attempts": 50,
"seed_for_randomness": 0, # choose None for pseudorandom
"create_handle": True,
# this part is only required for GridWorldSampler
"allow_clockwise": True, # allow both clockwise and counterclockwise rotating revolute joints
"epsilon": 0.1, # reduce the edge length of every box by epsilon
# this part is only required for ContinuousSpaceSampler
"start_planning_time": 0.25,
"planning_time_multiplier": 2., # apply for sampling of next link+joint after successfully sampling one link+joint
"first_test_time_multiplier": 1.5, # during the first test the link+joint is immovable and the puzzle must be
# unsolvable. to make sure that it is really UNsolvable, we must provide more
# planning time than in the second test (where we just check solvability)
"area_size": 3,
"upper_limit_prismatic": (2, 4), # random upper limit will be within this interval, lower limit is always 0
"upper_limit_revolute": (calc.RAD90, calc.RAD180), # same here (but there is a 50 % chance for the joint to be
# clockwise)
# this part is only required for Lockbox2017Sampler and LockboxRandomSampler
"mesh1": "input-meshes/slot_disc.blend", # both absolute and relative paths are allowed
# this part is only required for EscapeRoomSampler and MoveTwiceSampler
"robot_mesh": "input-meshes/droids.blend", # both absolute and relative paths are allowed
}
# set up world according to world_config
world = BlenderWorld(world_config)
BENCHMARK_RUNS = 1
VERSIONS = 1
for i in range(VERSIONS):
sampler_config["number_prismatic_joints"] = 4
sampler_config["puzzle_name"] = "simple_sliders_v" + str(i)
sampler = SimpleSlidersSampler(sampler_config, world)
sampler.build()
robowflex_simulation.solve(world.urdf_path, planning_time=10., benchmark_runs=BENCHMARK_RUNS)
# pybullet_simulation.solve(world.urdf_path, sampler.start_state, sampler.goal_space, 10., True)
sampler_config["number_prismatic_joints"] = 2
sampler_config["number_revolute_joints"] = 3
sampler_config["epsilon"] = 0.1
sampler_config["seed_for_randomness"] = i
sampler_config["puzzle_name"] = "grid_world_v" + str(i)
sampler = GridWorldSampler(sampler_config, world)
sampler.build()
robowflex_simulation.solve(world.urdf_path, planning_time=30., benchmark_runs=BENCHMARK_RUNS)
# pybullet_simulation.solve(world.urdf_path, sampler.start_state, sampler.goal_space, 10., True)
sampler_config["number_prismatic_joints"] = 2
sampler_config["number_revolute_joints"] = 2
sampler_config["seed_for_randomness"] = i
sampler_config["puzzle_name"] = "continuous_space_v" + str(i)
sampler = ContinuousSpaceSampler(sampler_config, world)
sampler.build()
robowflex_simulation.solve(world.urdf_path, planning_time=1., benchmark_runs=BENCHMARK_RUNS)
# pybullet_simulation.solve(world.urdf_path, sampler.start_state, sampler.goal_space, 10., True)
sampler_config["iterations"] = 2
sampler_config["slider_length"] = 1.4
sampler_config["slider_width"] = 0.2
sampler_config["seed_for_randomness"] = i
sampler_config["puzzle_name"] = "lockbox_random_v" + str(i)
sampler = LockboxRandomSampler(sampler_config, world)
sampler.build()
robowflex_simulation.solve(world.urdf_path, planning_time=30., benchmark_runs=BENCHMARK_RUNS)
# pybullet_simulation.solve(world.urdf_path, sampler.start_state, sampler.goal_space, 10., True)
sampler_config["puzzle_name"] = "escape_room_v" + str(i)
sampler = EscapeRoomSampler(sampler_config, world)
sampler.build()
robowflex_simulation.solve(world.urdf_path, planning_time=15., benchmark_runs=BENCHMARK_RUNS)
sampler_config["puzzle_name"] = "move_twice_v" + str(i)
sampler = MoveTwiceSampler(sampler_config, world)
sampler.build()
robowflex_simulation.solve(world.urdf_path, planning_time=10., benchmark_runs=BENCHMARK_RUNS)
# sampler_config["puzzle_name"] = "lockbox2017_v" + str(i)
# sampler = Lockbox2017Sampler(sampler_config, world)
# sampler.build()
# robowflex_simulation.solve(world.urdf_path, planning_time=1)