def load_scene_mesh(self):
        """
        Load scene mesh
        """
        filename = os.path.join(get_scene_path(self.scene_id),
                                "mesh_z_up_downsampled.obj")
        if not os.path.isfile(filename):
            filename = os.path.join(get_scene_path(self.scene_id),
                                    "mesh_z_up.obj")

        collision_id = p.createCollisionShape(
            p.GEOM_MESH, fileName=filename, flags=p.GEOM_FORCE_CONCAVE_TRIMESH)
        if self.pybullet_load_texture:
            visual_id = p.createVisualShape(p.GEOM_MESH, fileName=filename)
        else:
            visual_id = -1

        self.mesh_body_id = p.createMultiBody(
            baseCollisionShapeIndex=collision_id,
            baseVisualShapeIndex=visual_id)
        p.changeDynamics(self.mesh_body_id, -1, lateralFriction=1)

        if self.pybullet_load_texture:
            texture_filename = get_texture_file(filename)
            if texture_filename is not None:
                texture_id = p.loadTexture(texture_filename)
                p.changeVisualShape(self.mesh_body_id,
                                    -1,
                                    textureUniqueId=texture_id)
def main():
    scene_id = 'Rs'
    trav_map_original_size = 1000
    trav_map_size = 200
    trav_map_erosion = 2
    floor_map = []
    floor_graph = []

    with open(os.path.join(get_scene_path(scene_id), 'floors.txt'), 'r') as f:
        floors = sorted(list(map(float, f.readlines())))
        print('floor_heights', floors)

    for f in range(len(floors)):
        trav_map = Image.open(
            os.path.join(get_scene_path(scene_id),
                         'floor_trav_{}.png'.format(f)))
        obstacle_map = Image.open(
            os.path.join(get_scene_path(scene_id), 'floor_{}.png'.format(f)))
        trav_map = np.array(trav_map.resize((trav_map_size, trav_map_size)))
        obstacle_map = np.array(
            obstacle_map.resize((trav_map_size, trav_map_size)))
        trav_map[obstacle_map == 0] = 0
        trav_map = cv2.erode(trav_map,
                             np.ones((trav_map_erosion, trav_map_erosion)))
        plt.figure(f, figsize=(12, 12))
        plt.imshow(trav_map)

    plt.show()
def main():
    if len(sys.argv) > 1:
        model_path = sys.argv[1]
    else:
        model_path = os.path.join(get_scene_path('Rs'), 'mesh_z_up.obj')

    renderer = MeshRendererG2G(width=512, height=512, device_idx=0)
    renderer.load_object(model_path)
    renderer.add_instance(0)

    print(renderer.visual_objects, renderer.instances)
    print(renderer.materials_mapping, renderer.mesh_materials)
    camera_pose = np.array([0, 0, 1.2])
    view_direction = np.array([1, 0, 0])
    renderer.set_camera(camera_pose, camera_pose + view_direction, [0, 0, 1])
    renderer.set_fov(90)
    for i in range(3000):
        with Profiler('Render'):
            frame = renderer.render(modes=('rgb', 'normal', '3d'))

    print(frame)
    img_np = frame[0].flip(0).data.cpu().numpy().reshape(
        renderer.height, renderer.width, 4)
    normal_np = frame[1].flip(0).data.cpu().numpy().reshape(
        renderer.height, renderer.width, 4)
    plt.imshow(np.concatenate([img_np, normal_np], axis=1))
    plt.show()
    def load(self):
        """
        Load the scene (including scene mesh and floor plane) into pybullet
        """
        self.load_floor_metadata()
        self.load_scene_mesh()
        self.load_floor_planes()

        self.load_trav_map(get_scene_path(self.scene_id))
        return [self.mesh_body_id] + self.floor_body_ids
 def load_floor_metadata(self):
     """
     Load floor metadata
     """
     floor_height_path = os.path.join(get_scene_path(self.scene_id),
                                      'floors.txt')
     if not os.path.isfile(floor_height_path):
         raise Exception(
             'floor_heights.txt cannot be found in model: {}'.format(
                 self.scene_id))
     with open(floor_height_path, 'r') as f:
         self.floor_heights = sorted(list(map(float, f.readlines())))
         logging.debug('Floors {}'.format(self.floor_heights))
def main():
    if len(sys.argv) > 1:
        model_path = sys.argv[1]
    else:
        model_path = os.path.join(get_scene_path('Rs'), 'mesh_z_up.obj')

    p.connect(p.GUI)
    p.setGravity(0, 0, -9.8)
    p.setTimeStep(1./240.)

    # Load scenes
    collision_id = p.createCollisionShape(p.GEOM_MESH,
                                          fileName=model_path,
                                          meshScale=1.0,
                                          flags=p.GEOM_FORCE_CONCAVE_TRIMESH)
    visual_id = p.createVisualShape(p.GEOM_MESH,
                                    fileName=model_path,
                                    meshScale=1.0)

    mesh_id = p.createMultiBody(baseCollisionShapeIndex=collision_id,
                                baseVisualShapeIndex=visual_id)

    # Load robots
    turtlebot_urdf = os.path.join(
        gibson2.assets_path, 'models/turtlebot/turtlebot.urdf')
    robot_id = p.loadURDF(
        turtlebot_urdf, flags=p.URDF_USE_MATERIAL_COLORS_FROM_MTL)

    # Load objects
    obj_visual_filename = os.path.join(
        gibson2.assets_path, 'models/ycb/002_master_chef_can/textured_simple.obj')
    obj_collision_filename = os.path.join(
        gibson2.assets_path, 'models/ycb/002_master_chef_can/textured_simple_vhacd.obj')
    collision_id = p.createCollisionShape(p.GEOM_MESH,
                                          fileName=obj_collision_filename,
                                          meshScale=1.0)
    visual_id = p.createVisualShape(p.GEOM_MESH,
                                    fileName=obj_visual_filename,
                                    meshScale=1.0)
    object_id = p.createMultiBody(baseCollisionShapeIndex=collision_id,
                                  baseVisualShapeIndex=visual_id,
                                  basePosition=[1.0, 0.0, 1.0],
                                  baseMass=0.1)

    for _ in range(10000):
        p.stepSimulation()

    p.disconnect()
Esempio n. 7
0
def main():
    if len(sys.argv) > 1:
        model_path = sys.argv[1]
    else:
        model_path = os.path.join(get_scene_path('Rs'), 'mesh_z_up.obj')

    renderer = MeshRenderer(width=512, height=512)
    renderer.load_object(model_path)
    renderer.add_instance(0)
    camera_pose = np.array([0, 0, 1.2])
    view_direction = np.array([1, 0, 0])
    renderer.set_camera(camera_pose, camera_pose + view_direction, [0, 0, 1])
    renderer.set_fov(90)
    frames = renderer.render(
        modes=('rgb', 'normal', '3d'))
    frames = cv2.cvtColor(np.concatenate(frames, axis=1), cv2.COLOR_RGB2BGR)
    cv2.imshow('image', frames)
    cv2.waitKey(0)
def main():
    global _mouse_ix, _mouse_iy, down, view_direction

    if len(sys.argv) > 1:
        model_path = sys.argv[1]
    else:
        model_path = os.path.join(get_scene_path('Rs'), 'mesh_z_up.obj')

    renderer = MeshRenderer(width=512, height=512)
    renderer.load_object(model_path)

    renderer.add_instance(0)
    print(renderer.visual_objects, renderer.instances)
    print(renderer.materials_mapping, renderer.mesh_materials)

    px = 0
    py = 0.2

    camera_pose = np.array([px, py, 0.5])
    view_direction = np.array([0, -1, -1])
    renderer.set_camera(camera_pose, camera_pose + view_direction, [0, 0, 1])
    renderer.set_fov(90)

    _mouse_ix, _mouse_iy = -1, -1
    down = False

    def change_dir(event, x, y, flags, param):
        global _mouse_ix, _mouse_iy, down, view_direction
        if event == cv2.EVENT_LBUTTONDOWN:
            _mouse_ix, _mouse_iy = x, y
            down = True
        if event == cv2.EVENT_MOUSEMOVE:
            if down:
                dx = (x - _mouse_ix) / 100.0
                dy = (y - _mouse_iy) / 100.0
                _mouse_ix = x
                _mouse_iy = y
                r1 = np.array([[np.cos(dy), 0, np.sin(dy)], [0, 1, 0],
                               [-np.sin(dy), 0, np.cos(dy)]])
                r2 = np.array([[np.cos(-dx), -np.sin(-dx), 0],
                               [np.sin(-dx), np.cos(-dx), 0], [0, 0, 1]])
                view_direction = r1.dot(r2).dot(view_direction)
        elif event == cv2.EVENT_LBUTTONUP:
            down = False

    cv2.namedWindow('test')
    cv2.setMouseCallback('test', change_dir)

    while True:
        with Profiler('Render'):
            frame = renderer.render(modes=('rgb'))
        cv2.imshow(
            'test',
            cv2.cvtColor(np.concatenate(frame, axis=1), cv2.COLOR_RGB2BGR))
        q = cv2.waitKey(1)
        if q == ord('w'):
            px += 0.01
        elif q == ord('s'):
            px -= 0.01
        elif q == ord('a'):
            py += 0.01
        elif q == ord('d'):
            py -= 0.01
        elif q == ord('q'):
            break
        camera_pose = np.array([px, py, 0.5])
        renderer.set_camera(camera_pose, camera_pose + view_direction,
                            [0, 0, 1])

    renderer.release()
Esempio n. 9
0
def main():
    global _mouse_ix, _mouse_iy, down, view_direction

    if len(sys.argv) > 1:
        model_path = sys.argv[1]
    else:
        model_path = os.path.join(get_scene_path('Rs_int'), 'mesh_z_up.obj')
    settings = MeshRendererSettings(msaa=True, enable_shadow=True)
    renderer = MeshRenderer(width=1024, height=1024,  vertical_fov=70, rendering_settings=settings)
    renderer.set_light_position_direction([0,0,10], [0,0,0])

    i = 0

    v = []
    for fn in os.listdir(model_path):
        if fn.endswith('obj'):
            vertices, faces = load_obj_np(os.path.join(model_path, fn))
            v.append(vertices)

    v = np.vstack(v)
    print(v.shape)
    xlen = np.max(v[:,0]) - np.min(v[:,0])
    ylen = np.max(v[:,1]) - np.min(v[:,1])
    scale = 2.0/(max(xlen, ylen))

    for fn in os.listdir(model_path):
        if fn.endswith('obj'):
            renderer.load_object(os.path.join(model_path, fn), scale=[scale, scale, scale])
            renderer.add_instance(i)
            i += 1

    print(renderer.visual_objects, renderer.instances)
    print(renderer.materials_mapping, renderer.mesh_materials)

    px = 1
    py = 1
    pz = 1

    camera_pose = np.array([px, py, pz])
    view_direction = np.array([-1, -1, -1])
    renderer.set_camera(camera_pose, camera_pose + view_direction, [0, 0, 1])

    _mouse_ix, _mouse_iy = -1, -1
    down = False

    def change_dir(event, x, y, flags, param):
        global _mouse_ix, _mouse_iy, down, view_direction
        if event == cv2.EVENT_LBUTTONDOWN:
            _mouse_ix, _mouse_iy = x, y
            down = True
        if event == cv2.EVENT_MOUSEMOVE:
            if down:
                dx = (x - _mouse_ix) / 100.0
                dy = (y - _mouse_iy) / 100.0
                _mouse_ix = x
                _mouse_iy = y
                r1 = np.array([[np.cos(dy), 0, np.sin(dy)], [0, 1, 0], [-np.sin(dy), 0, np.cos(dy)]])
                r2 = np.array([[np.cos(-dx), -np.sin(-dx), 0], [np.sin(-dx), np.cos(-dx), 0], [0, 0, 1]])
                view_direction = r1.dot(r2).dot(view_direction)
        elif event == cv2.EVENT_LBUTTONUP:
            down = False

    cv2.namedWindow('test')
    cv2.setMouseCallback('test', change_dir)

    while True:
        with Profiler('Render'):
            frame = renderer.render(modes=('rgb', 'normal'))
        cv2.imshow('test', cv2.cvtColor(np.concatenate(frame, axis=1), cv2.COLOR_RGB2BGR))

        q = cv2.waitKey(1)
        if q == ord('w'):
            px += 0.1
        elif q == ord('s'):
            px -= 0.1
        elif q == ord('a'):
            py += 0.1
        elif q == ord('d'):
            py -= 0.1
        elif q == ord('q'):
            break

        camera_pose = np.array([px, py, 1])
        renderer.set_camera(camera_pose, camera_pose + view_direction, [0, 0, 1])

    renderer.release()