def plot_costmaps(): workspace = sample_circle_workspaces(nb_circles=4) grid_sparse = workspace.box.stacked_meshgrid(24) grid_dense = workspace.box.stacked_meshgrid(100) extent = workspace.box.box_extent() sdf = SignedDistanceWorkspaceMap(workspace) viewer = WorkspaceDrawer(workspace, wait_for_keyboard=True, rows=1, cols=2, scale=1.) viewer.set_drawing_axis(0) viewer.set_workspace(workspace) viewer.draw_ws_img(sdf(grid_dense).T) viewer.draw_ws_obstacles() viewer.set_drawing_axis(1) viewer.set_workspace(workspace) viewer.draw_ws_img(sdf(grid_sparse).T) viewer.draw_ws_obstacles() viewer.show_once()
# PERFORMANCE OF THIS SOFTWARE. # # Jim Mainprice on Sunday June 13 2018 import demos_common_imports from pyrieef.geometry.workspace import * from pyrieef.geometry.pixel_map import sdf from pyrieef.rendering.workspace_renderer import WorkspaceDrawer import scipy.misc from scipy.misc import imresize env = EnvBox(dim=np.array([2., 2.])) box = Box(origin=np.array([-.2, -.2])) segment = Segment(origin=np.array([.4, -.1]), orientation=0.2) circle = Circle(origin=np.array([.5, .5]), radius=0.2) workspace = Workspace(env) workspace.obstacles.append(box) workspace.obstacles.append(segment) workspace.obstacles.append(circle) viewer = WorkspaceDrawer(workspace, wait_for_keyboard=True) nb_points = 20 occupancy_map = occupancy_map(nb_points, workspace) signed_distance_field = sdf(occupancy_map) # viewer.draw_ws_img(occupancy_map) viewer.draw_ws_img( ndimage.gaussian_filter(imresize(signed_distance_field, (300, 300), 'nearest'), sigma=3)) viewer.draw_ws_obstacles() viewer.show_once()