forked from simpler-env/SimplerEnv
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathocto_pick_coke_can_variant_agg.sh
182 lines (112 loc) · 6.05 KB
/
octo_pick_coke_can_variant_agg.sh
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
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
gpu_id=0
declare -a arr=("octo-base")
# lr_switch=laying horizontally but flipped left-right to match real eval; upright=standing; laid_vertically=laying vertically
declare -a coke_can_options_arr=("lr_switch=True" "upright=True" "laid_vertically=True")
for policy_model in "${arr[@]}"; do echo "$policy_model"; done
# base setup
env_name=GraspSingleOpenedCokeCanInScene-v0
scene_name=google_pick_coke_can_1_v4
for coke_can_option in "${coke_can_options_arr[@]}";
do for policy_model in "${arr[@]}";
do CUDA_VISIBLE_DEVICES=${gpu_id} python simpler_env/main_inference.py --policy-model ${policy_model} --ckpt-path None \
--robot google_robot_static \
--control-freq 3 --sim-freq 513 --max-episode-steps 80 \
--env-name ${env_name} --scene-name ${scene_name} \
--robot-init-x 0.35 0.35 1 --robot-init-y 0.20 0.20 1 --obj-init-x -0.35 -0.12 5 --obj-init-y -0.02 0.42 5 \
--robot-init-rot-quat-center 0 0 0 1 --robot-init-rot-rpy-range 0 0 1 0 0 1 0 0 1 \
--additional-env-build-kwargs ${coke_can_option};
done
done
# table textures
env_name=GraspSingleOpenedCokeCanInScene-v0
declare -a scene_arr=("Baked_sc1_staging_objaverse_cabinet1_h870" \
"Baked_sc1_staging_objaverse_cabinet2_h870")
for coke_can_option in "${coke_can_options_arr[@]}";
do for scene_name in "${scene_arr[@]}";
do for policy_model in "${arr[@]}";
do CUDA_VISIBLE_DEVICES=${gpu_id} python simpler_env/main_inference.py --policy-model ${policy_model} --ckpt-path None \
--robot google_robot_static \
--control-freq 3 --sim-freq 513 --max-episode-steps 80 \
--env-name ${env_name} --scene-name ${scene_name} \
--robot-init-x 0.35 0.35 1 --robot-init-y 0.20 0.20 1 --obj-init-x -0.35 -0.12 5 --obj-init-y -0.02 0.42 5 \
--robot-init-rot-quat-center 0 0 0 1 --robot-init-rot-rpy-range 0 0 1 0 0 1 0 0 1 \
--additional-env-build-kwargs ${coke_can_option};
done
done
done
# distractors
env_name=GraspSingleOpenedCokeCanDistractorInScene-v0
scene_name=google_pick_coke_can_1_v4
for coke_can_option in "${coke_can_options_arr[@]}";
do for policy_model in "${arr[@]}";
do CUDA_VISIBLE_DEVICES=${gpu_id} python simpler_env/main_inference.py --policy-model ${policy_model} --ckpt-path None \
--robot google_robot_static \
--control-freq 3 --sim-freq 513 --max-episode-steps 80 \
--env-name ${env_name} --scene-name ${scene_name} \
--robot-init-x 0.35 0.35 1 --robot-init-y 0.20 0.20 1 --obj-init-x -0.35 -0.12 5 --obj-init-y -0.02 0.42 5 \
--robot-init-rot-quat-center 0 0 0 1 --robot-init-rot-rpy-range 0 0 1 0 0 1 0 0 1 \
--additional-env-build-kwargs ${coke_can_option};
CUDA_VISIBLE_DEVICES=${gpu_id} python simpler_env/main_inference.py --policy-model ${policy_model} --ckpt-path None \
--robot google_robot_static \
--control-freq 3 --sim-freq 513 --max-episode-steps 80 \
--env-name ${env_name} --scene-name ${scene_name} \
--robot-init-x 0.35 0.35 1 --robot-init-y 0.20 0.20 1 --obj-init-x -0.35 -0.12 5 --obj-init-y -0.02 0.42 5 \
--robot-init-rot-quat-center 0 0 0 1 --robot-init-rot-rpy-range 0 0 1 0 0 1 0 0 1 \
--additional-env-build-kwargs ${coke_can_option} distractor_config=more;
done
done
# backgrounds
env_name=GraspSingleOpenedCokeCanInScene-v0
declare -a scene_arr=("google_pick_coke_can_1_v4_alt_background" \
"google_pick_coke_can_1_v4_alt_background_2")
for coke_can_option in "${coke_can_options_arr[@]}";
do for scene_name in "${scene_arr[@]}";
do for policy_model in "${arr[@]}";
do CUDA_VISIBLE_DEVICES=${gpu_id} python simpler_env/main_inference.py --policy-model ${policy_model} --ckpt-path None \
--robot google_robot_static \
--control-freq 3 --sim-freq 513 --max-episode-steps 80 \
--env-name ${env_name} --scene-name ${scene_name} \
--robot-init-x 0.35 0.35 1 --robot-init-y 0.20 0.20 1 --obj-init-x -0.35 -0.12 5 --obj-init-y -0.02 0.42 5 \
--robot-init-rot-quat-center 0 0 0 1 --robot-init-rot-rpy-range 0 0 1 0 0 1 0 0 1 \
--additional-env-build-kwargs ${coke_can_option};
done
done
done
# lightings
env_name=GraspSingleOpenedCokeCanInScene-v0
scene_name=google_pick_coke_can_1_v4
for coke_can_option in "${coke_can_options_arr[@]}";
do for policy_model in "${arr[@]}";
do CUDA_VISIBLE_DEVICES=${gpu_id} python simpler_env/main_inference.py --policy-model ${policy_model} --ckpt-path None \
--robot google_robot_static \
--control-freq 3 --sim-freq 513 --max-episode-steps 80 \
--env-name ${env_name} --scene-name ${scene_name} \
--robot-init-x 0.35 0.35 1 --robot-init-y 0.20 0.20 1 --obj-init-x -0.35 -0.12 5 --obj-init-y -0.02 0.42 5 \
--robot-init-rot-quat-center 0 0 0 1 --robot-init-rot-rpy-range 0 0 1 0 0 1 0 0 1 \
--additional-env-build-kwargs ${coke_can_option} slightly_darker_lighting=True;
CUDA_VISIBLE_DEVICES=${gpu_id} python simpler_env/main_inference.py --policy-model ${policy_model} --ckpt-path None \
--robot google_robot_static \
--control-freq 3 --sim-freq 513 --max-episode-steps 80 \
--env-name ${env_name} --scene-name ${scene_name} \
--robot-init-x 0.35 0.35 1 --robot-init-y 0.20 0.20 1 --obj-init-x -0.35 -0.12 5 --obj-init-y -0.02 0.42 5 \
--robot-init-rot-quat-center 0 0 0 1 --robot-init-rot-rpy-range 0 0 1 0 0 1 0 0 1 \
--additional-env-build-kwargs ${coke_can_option} slightly_brighter_lighting=True;
done
done
# camera orientations
declare -a env_arr=("GraspSingleOpenedCokeCanAltGoogleCameraInScene-v0" \
"GraspSingleOpenedCokeCanAltGoogleCamera2InScene-v0")
scene_name=google_pick_coke_can_1_v4
for coke_can_option in "${coke_can_options_arr[@]}";
do for env_name in "${env_arr[@]}";
do for policy_model in "${arr[@]}";
do CUDA_VISIBLE_DEVICES=${gpu_id} python simpler_env/main_inference.py --policy-model ${policy_model} --ckpt-path None \
--robot google_robot_static \
--control-freq 3 --sim-freq 513 --max-episode-steps 80 \
--env-name ${env_name} --scene-name ${scene_name} \
--robot-init-x 0.35 0.35 1 --robot-init-y 0.20 0.20 1 --obj-init-x -0.35 -0.12 5 --obj-init-y -0.02 0.42 5 \
--robot-init-rot-quat-center 0 0 0 1 --robot-init-rot-rpy-range 0 0 1 0 0 1 0 0 1 \
--additional-env-build-kwargs ${coke_can_option};
done
done
done