File size: 18,181 Bytes
a32fcea | 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 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 | from multiprocessing import Process, Manager
from pyrep.const import RenderMode
from rlbench import ObservationConfig
from rlbench.action_modes.action_mode import MoveArmThenGripper
from rlbench.action_modes.arm_action_modes import JointVelocity
from rlbench.action_modes.gripper_action_modes import Discrete
from rlbench.backend.utils import task_file_to_task_class
from rlbench.environment import Environment
import rlbench.backend.task as task
import os
import pickle
from PIL import Image
from rlbench.backend import utils
from rlbench.backend.const import *
import numpy as np
from absl import app
from absl import flags
FLAGS = flags.FLAGS
flags.DEFINE_string('save_path',
'/tmp/rlbench_data/',
'Where to save the demos.')
flags.DEFINE_list('tasks', [],
'The tasks to collect. If empty, all tasks are collected.')
flags.DEFINE_list('image_size', [128, 128],
'The size of the images tp save.')
flags.DEFINE_enum('renderer', 'opengl3', ['opengl', 'opengl3'],
'The renderer to use. opengl does not include shadows, '
'but is faster.')
flags.DEFINE_integer('processes', 1,
'The number of parallel processes during collection.')
flags.DEFINE_integer('episodes_per_task', 10,
'The number of episodes to collect per task.')
flags.DEFINE_integer('variations', -1,
'Number of variations to collect per task. -1 for all.')
flags.DEFINE_bool('all_variations', True,
'Include all variations when sampling epsiodes')
def check_and_make(dir):
if not os.path.exists(dir):
os.makedirs(dir)
def save_demo(demo, example_path, variation):
# Save image data first, and then None the image data, and pickle
left_shoulder_rgb_path = os.path.join(
example_path, LEFT_SHOULDER_RGB_FOLDER)
left_shoulder_depth_path = os.path.join(
example_path, LEFT_SHOULDER_DEPTH_FOLDER)
left_shoulder_mask_path = os.path.join(
example_path, LEFT_SHOULDER_MASK_FOLDER)
right_shoulder_rgb_path = os.path.join(
example_path, RIGHT_SHOULDER_RGB_FOLDER)
right_shoulder_depth_path = os.path.join(
example_path, RIGHT_SHOULDER_DEPTH_FOLDER)
right_shoulder_mask_path = os.path.join(
example_path, RIGHT_SHOULDER_MASK_FOLDER)
overhead_rgb_path = os.path.join(
example_path, OVERHEAD_RGB_FOLDER)
overhead_depth_path = os.path.join(
example_path, OVERHEAD_DEPTH_FOLDER)
overhead_mask_path = os.path.join(
example_path, OVERHEAD_MASK_FOLDER)
wrist_rgb_path = os.path.join(example_path, WRIST_RGB_FOLDER)
wrist_depth_path = os.path.join(example_path, WRIST_DEPTH_FOLDER)
wrist_mask_path = os.path.join(example_path, WRIST_MASK_FOLDER)
front_rgb_path = os.path.join(example_path, FRONT_RGB_FOLDER)
front_depth_path = os.path.join(example_path, FRONT_DEPTH_FOLDER)
front_mask_path = os.path.join(example_path, FRONT_MASK_FOLDER)
check_and_make(left_shoulder_rgb_path)
check_and_make(left_shoulder_depth_path)
check_and_make(left_shoulder_mask_path)
check_and_make(right_shoulder_rgb_path)
check_and_make(right_shoulder_depth_path)
check_and_make(right_shoulder_mask_path)
check_and_make(overhead_rgb_path)
check_and_make(overhead_depth_path)
check_and_make(overhead_mask_path)
check_and_make(wrist_rgb_path)
check_and_make(wrist_depth_path)
check_and_make(wrist_mask_path)
check_and_make(front_rgb_path)
check_and_make(front_depth_path)
check_and_make(front_mask_path)
for i, obs in enumerate(demo):
left_shoulder_rgb = Image.fromarray(obs.left_shoulder_rgb)
left_shoulder_depth = utils.float_array_to_rgb_image(
obs.left_shoulder_depth, scale_factor=DEPTH_SCALE)
left_shoulder_mask = Image.fromarray(
(obs.left_shoulder_mask * 255).astype(np.uint8))
right_shoulder_rgb = Image.fromarray(obs.right_shoulder_rgb)
right_shoulder_depth = utils.float_array_to_rgb_image(
obs.right_shoulder_depth, scale_factor=DEPTH_SCALE)
right_shoulder_mask = Image.fromarray(
(obs.right_shoulder_mask * 255).astype(np.uint8))
overhead_rgb = Image.fromarray(obs.overhead_rgb)
overhead_depth = utils.float_array_to_rgb_image(
obs.overhead_depth, scale_factor=DEPTH_SCALE)
overhead_mask = Image.fromarray(
(obs.overhead_mask * 255).astype(np.uint8))
wrist_rgb = Image.fromarray(obs.wrist_rgb)
wrist_depth = utils.float_array_to_rgb_image(
obs.wrist_depth, scale_factor=DEPTH_SCALE)
wrist_mask = Image.fromarray((obs.wrist_mask * 255).astype(np.uint8))
front_rgb = Image.fromarray(obs.front_rgb)
front_depth = utils.float_array_to_rgb_image(
obs.front_depth, scale_factor=DEPTH_SCALE)
front_mask = Image.fromarray((obs.front_mask * 255).astype(np.uint8))
left_shoulder_rgb.save(
os.path.join(left_shoulder_rgb_path, IMAGE_FORMAT % i))
left_shoulder_depth.save(
os.path.join(left_shoulder_depth_path, IMAGE_FORMAT % i))
left_shoulder_mask.save(
os.path.join(left_shoulder_mask_path, IMAGE_FORMAT % i))
right_shoulder_rgb.save(
os.path.join(right_shoulder_rgb_path, IMAGE_FORMAT % i))
right_shoulder_depth.save(
os.path.join(right_shoulder_depth_path, IMAGE_FORMAT % i))
right_shoulder_mask.save(
os.path.join(right_shoulder_mask_path, IMAGE_FORMAT % i))
overhead_rgb.save(
os.path.join(overhead_rgb_path, IMAGE_FORMAT % i))
overhead_depth.save(
os.path.join(overhead_depth_path, IMAGE_FORMAT % i))
overhead_mask.save(
os.path.join(overhead_mask_path, IMAGE_FORMAT % i))
wrist_rgb.save(os.path.join(wrist_rgb_path, IMAGE_FORMAT % i))
wrist_depth.save(os.path.join(wrist_depth_path, IMAGE_FORMAT % i))
wrist_mask.save(os.path.join(wrist_mask_path, IMAGE_FORMAT % i))
front_rgb.save(os.path.join(front_rgb_path, IMAGE_FORMAT % i))
front_depth.save(os.path.join(front_depth_path, IMAGE_FORMAT % i))
front_mask.save(os.path.join(front_mask_path, IMAGE_FORMAT % i))
# We save the images separately, so set these to None for pickling.
obs.left_shoulder_rgb = None
obs.left_shoulder_depth = None
obs.left_shoulder_point_cloud = None
obs.left_shoulder_mask = None
obs.right_shoulder_rgb = None
obs.right_shoulder_depth = None
obs.right_shoulder_point_cloud = None
obs.right_shoulder_mask = None
obs.overhead_rgb = None
obs.overhead_depth = None
obs.overhead_point_cloud = None
obs.overhead_mask = None
obs.wrist_rgb = None
obs.wrist_depth = None
obs.wrist_point_cloud = None
obs.wrist_mask = None
obs.front_rgb = None
obs.front_depth = None
obs.front_point_cloud = None
obs.front_mask = None
# Save the low-dimension data
with open(os.path.join(example_path, LOW_DIM_PICKLE), 'wb') as f:
pickle.dump(demo, f)
with open(os.path.join(example_path, VARIATION_NUMBER), 'wb') as f:
pickle.dump(variation, f)
def run(i, lock, task_index, variation_count, results, file_lock, tasks):
"""Each thread will choose one task and variation, and then gather
all the episodes_per_task for that variation."""
# Initialise each thread with random seed
np.random.seed(None)
num_tasks = len(tasks)
img_size = list(map(int, FLAGS.image_size))
obs_config = ObservationConfig()
obs_config.set_all(True)
obs_config.right_shoulder_camera.image_size = img_size
obs_config.left_shoulder_camera.image_size = img_size
obs_config.overhead_camera.image_size = img_size
obs_config.wrist_camera.image_size = img_size
obs_config.front_camera.image_size = img_size
# Store depth as 0 - 1
obs_config.right_shoulder_camera.depth_in_meters = False
obs_config.left_shoulder_camera.depth_in_meters = False
obs_config.overhead_camera.depth_in_meters = False
obs_config.wrist_camera.depth_in_meters = False
obs_config.front_camera.depth_in_meters = False
# We want to save the masks as rgb encodings.
obs_config.left_shoulder_camera.masks_as_one_channel = False
obs_config.right_shoulder_camera.masks_as_one_channel = False
obs_config.overhead_camera.masks_as_one_channel = False
obs_config.wrist_camera.masks_as_one_channel = False
obs_config.front_camera.masks_as_one_channel = False
if FLAGS.renderer == 'opengl':
obs_config.right_shoulder_camera.render_mode = RenderMode.OPENGL
obs_config.left_shoulder_camera.render_mode = RenderMode.OPENGL
obs_config.overhead_camera.render_mode = RenderMode.OPENGL
obs_config.wrist_camera.render_mode = RenderMode.OPENGL
obs_config.front_camera.render_mode = RenderMode.OPENGL
rlbench_env = Environment(
action_mode=MoveArmThenGripper(JointVelocity(), Discrete()),
obs_config=obs_config,
headless=True)
rlbench_env.launch()
task_env = None
tasks_with_problems = results[i] = ''
while True:
# Figure out what task/variation this thread is going to do
with lock:
if task_index.value >= num_tasks:
print('Process', i, 'finished')
break
my_variation_count = variation_count.value
t = tasks[task_index.value]
task_env = rlbench_env.get_task(t)
var_target = task_env.variation_count()
if FLAGS.variations >= 0:
var_target = np.minimum(FLAGS.variations, var_target)
if my_variation_count >= var_target:
# If we have reached the required number of variations for this
# task, then move on to the next task.
variation_count.value = my_variation_count = 0
task_index.value += 1
variation_count.value += 1
if task_index.value >= num_tasks:
print('Process', i, 'finished')
break
t = tasks[task_index.value]
variation_path = os.path.join(
FLAGS.save_path, task_env.get_name(),
VARIATIONS_FOLDER % my_variation_count)
check_and_make(variation_path)
episodes_path = os.path.join(variation_path, EPISODES_FOLDER)
check_and_make(episodes_path)
abort_variation = False
for ex_idx in range(FLAGS.episodes_per_task):
print('Process', i, '// Task:', task_env.get_name(),
'// Variation:', my_variation_count, '// Demo:', ex_idx)
attempts = 10
while attempts > 0:
try:
task_env = rlbench_env.get_task(t)
task_env.set_variation(my_variation_count)
descriptions, obs = task_env.reset()
# TODO: for now we do the explicit looping.
demo, = task_env.get_demos(
amount=1,
live_demos=True)
except Exception as e:
attempts -= 1
if attempts > 0:
continue
problem = (
'Process %d failed collecting task %s (variation: %d, '
'example: %d). Skipping this task/variation.\n%s\n' % (
i, task_env.get_name(), my_variation_count, ex_idx,
str(e))
)
print(problem)
tasks_with_problems += problem
abort_variation = True
break
episode_path = os.path.join(episodes_path, EPISODE_FOLDER % ex_idx)
with file_lock:
save_demo(demo, episode_path, my_variation_count)
with open(os.path.join(
episode_path, VARIATION_DESCRIPTIONS), 'wb') as f:
pickle.dump(descriptions, f)
break
if abort_variation:
break
results[i] = tasks_with_problems
rlbench_env.shutdown()
def run_all_variations(i, lock, task_index, variation_count, results, file_lock, tasks):
"""Each thread will choose one task and variation, and then gather
all the episodes_per_task for that variation."""
# Initialise each thread with random seed
np.random.seed(None)
num_tasks = len(tasks)
img_size = list(map(int, FLAGS.image_size))
obs_config = ObservationConfig()
obs_config.set_all(True)
obs_config.right_shoulder_camera.image_size = img_size
obs_config.left_shoulder_camera.image_size = img_size
obs_config.overhead_camera.image_size = img_size
obs_config.wrist_camera.image_size = img_size
obs_config.front_camera.image_size = img_size
# Store depth as 0 - 1
obs_config.right_shoulder_camera.depth_in_meters = False
obs_config.left_shoulder_camera.depth_in_meters = False
obs_config.overhead_camera.depth_in_meters = False
obs_config.wrist_camera.depth_in_meters = False
obs_config.front_camera.depth_in_meters = False
# We want to save the masks as rgb encodings.
obs_config.left_shoulder_camera.masks_as_one_channel = False
obs_config.right_shoulder_camera.masks_as_one_channel = False
obs_config.overhead_camera.masks_as_one_channel = False
obs_config.wrist_camera.masks_as_one_channel = False
obs_config.front_camera.masks_as_one_channel = False
if FLAGS.renderer == 'opengl':
obs_config.right_shoulder_camera.render_mode = RenderMode.OPENGL
obs_config.left_shoulder_camera.render_mode = RenderMode.OPENGL
obs_config.overhead_camera.render_mode = RenderMode.OPENGL
obs_config.wrist_camera.render_mode = RenderMode.OPENGL
obs_config.front_camera.render_mode = RenderMode.OPENGL
rlbench_env = Environment(
action_mode=MoveArmThenGripper(JointVelocity(), Discrete()),
obs_config=obs_config,
headless=True)
rlbench_env.launch()
task_env = None
tasks_with_problems = results[i] = ''
while True:
# with lock:
if task_index.value >= num_tasks:
print('Process', i, 'finished')
break
t = tasks[task_index.value]
task_env = rlbench_env.get_task(t)
possible_variations = task_env.variation_count()
variation_path = os.path.join(
FLAGS.save_path, task_env.get_name(),
VARIATIONS_ALL_FOLDER)
check_and_make(variation_path)
episodes_path = os.path.join(variation_path, EPISODES_FOLDER)
check_and_make(episodes_path)
abort_variation = False
for ex_idx in range(FLAGS.episodes_per_task):
attempts = 10
while attempts > 0:
try:
variation = np.random.randint(possible_variations)
task_env = rlbench_env.get_task(t)
task_env.set_variation(variation)
descriptions, obs = task_env.reset()
print('Process', i, '// Task:', task_env.get_name(),
'// Variation:', variation, '// Demo:', ex_idx)
# TODO: for now we do the explicit looping.
demo, = task_env.get_demos(
amount=1,
live_demos=True)
except Exception as e:
attempts -= 1
if attempts > 0:
continue
problem = (
'Process %d failed collecting task %s (variation: %d, '
'example: %d). Skipping this task/variation.\n%s\n' % (
i, task_env.get_name(), variation, ex_idx,
str(e))
)
print(problem)
tasks_with_problems += problem
abort_variation = True
break
episode_path = os.path.join(episodes_path, EPISODE_FOLDER % ex_idx)
with file_lock:
save_demo(demo, episode_path, variation)
with open(os.path.join(
episode_path, VARIATION_DESCRIPTIONS), 'wb') as f:
pickle.dump(descriptions, f)
break
if abort_variation:
break
# with lock:
task_index.value += 1
results[i] = tasks_with_problems
rlbench_env.shutdown()
def main(argv):
task_files = [t.replace('.py', '') for t in os.listdir(task.TASKS_PATH)
if t != '__init__.py' and t.endswith('.py')]
if len(FLAGS.tasks) > 0:
for t in FLAGS.tasks:
if t not in task_files:
raise ValueError('Task %s not recognised!.' % t)
task_files = FLAGS.tasks
tasks = [task_file_to_task_class(t) for t in task_files]
manager = Manager()
result_dict = manager.dict()
file_lock = manager.Lock()
task_index = manager.Value('i', 0)
variation_count = manager.Value('i', 0)
lock = manager.Lock()
check_and_make(FLAGS.save_path)
if FLAGS.all_variations:
# multiprocessing for all_variations not support (for now)
run_all_variations(0, lock, task_index, variation_count, result_dict, file_lock, tasks)
else:
processes = [Process(
target=run, args=(
i, lock, task_index, variation_count, result_dict, file_lock,
tasks))
for i in range(FLAGS.processes)]
[t.start() for t in processes]
[t.join() for t in processes]
print('Data collection done!')
for i in range(FLAGS.processes):
print(result_dict[i])
if __name__ == '__main__':
app.run(main)
|