Source code for bulletarm.envs.block_structure_envs.house_building_1_env

from copy import deepcopy
from bulletarm.envs.base_env import BaseEnv
from bulletarm.pybullet.utils import constants
from bulletarm.pybullet.utils.constants import NoValidPositionException

[docs]class HouseBuilding1Env(BaseEnv): '''Open loop house building 1 task. The robot needs to first stack N-1 cubic blocks then place a triangle block on top of the stack. The number of blocks N is set by the config. Args: config (dict): Intialization arguments for the env ''' def __init__(self, config): # env specific parameters if 'object_scale_range' not in config: config['object_scale_range'] = [0.6, 0.6] if 'num_objects' not in config: config['num_objects'] = 4 if 'max_steps' not in config: config['max_steps'] = 10 super(HouseBuilding1Env, self).__init__(config) def reset(self): '''''' while True: self.resetPybulletWorkspace() try: self._generateShapes(constants.TRIANGLE, 1, random_orientation=self.random_orientation) self._generateShapes(constants.CUBE, self.num_obj-1, random_orientation=self.random_orientation) except NoValidPositionException as e: continue else: break return self._getObservation() def _checkTermination(self): '''''' blocks = list(filter(lambda x: self.object_types[x] == constants.CUBE, self.objects)) triangles = list(filter(lambda x: self.object_types[x] == constants.TRIANGLE, self.objects)) return self._checkStack(blocks+triangles) and self._checkObjUpright(triangles[0]) def isSimValid(self): triangles = list(filter(lambda x: self.object_types[x] == constants.TRIANGLE, self.objects)) return self._checkObjUpright(triangles[0]) and super(HouseBuilding1Env, self).isSimValid()
def createHouseBuilding1Env(config): return HouseBuilding1Env(config)