Skip to content

Commit

Permalink
Merge pull request AtsushiSakai#259 from goktug97/close_on_key
Browse files Browse the repository at this point in the history
Close on key
  • Loading branch information
AtsushiSakai authored Dec 14, 2019
2 parents bf86cc8 + 9ca7d8f commit ad5e1aa
Show file tree
Hide file tree
Showing 53 changed files with 168 additions and 8 deletions.
7 changes: 5 additions & 2 deletions AerialNavigation/drone_3d_trajectory_following/Quadrotor.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
import numpy as np
import matplotlib.pyplot as plt


class Quadrotor():
def __init__(self, x=0, y=0, z=0, roll=0, pitch=0, yaw=0, size=0.25, show_animation=True):
self.p1 = np.array([size / 2, 0, 0, 1]).T
Expand All @@ -24,6 +23,10 @@ def __init__(self, x=0, y=0, z=0, roll=0, pitch=0, yaw=0, size=0.25, show_animat
if self.show_animation:
plt.ion()
fig = plt.figure()
# for stopping simulation with the esc key.
fig.canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])

self.ax = fig.add_subplot(111, projection='3d')

self.update_pose(x, y, z, roll, pitch, yaw)
Expand Down Expand Up @@ -81,4 +84,4 @@ def plot(self): # pragma: no cover
plt.ylim(-5, 5)
self.ax.set_zlim(0, 10)

plt.pause(0.001)
plt.pause(0.001)
Original file line number Diff line number Diff line change
Expand Up @@ -567,6 +567,9 @@ def plot_animation(X, U): # pragma: no cover

fig = plt.figure()
ax = fig.gca(projection='3d')
# for stopping simulation with the esc key.
fig.canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])

for k in range(K):
plt.cla()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,9 @@ def astar_torus(grid, start_node, goal_node):
for i in range(1, len(route)):
grid[route[i]] = 6
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.imshow(grid, cmap=cmap, norm=norm, interpolation=None)
plt.show()
plt.pause(1e-2)
Expand Down Expand Up @@ -262,4 +265,4 @@ def plot(self, obstacles=[]): # pragma: no cover


if __name__ == '__main__':
main()
main()
Original file line number Diff line number Diff line change
Expand Up @@ -193,6 +193,9 @@ def astar_torus(grid, start_node, goal_node):
for i in range(1, len(route)):
grid[route[i]] = 6
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.imshow(grid, cmap=cmap, norm=norm, interpolation=None)
plt.show()
plt.pause(1e-2)
Expand Down
3 changes: 3 additions & 0 deletions ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,9 @@ def update_points(self):

def plot(self): # pragma: no cover
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])

for i in range(self.n_links + 1):
if i is not self.n_links:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,9 @@ def animation():
def main(): # pragma: no cover
fig = plt.figure()
fig.canvas.mpl_connect("button_press_event", click)
# for stopping simulation with the esc key.
fig.canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
two_joint_arm()


Expand Down
3 changes: 3 additions & 0 deletions Bipedal/bipedal_planner/bipedal_planner.py
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,9 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False):
if c > len(com_trajectory_for_plot):
# set up plotter
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
ax.set_zlim(0, z_c * 2)
ax.set_aspect('equal', 'datalim')

Expand Down
3 changes: 3 additions & 0 deletions Localization/ensemble_kalman_filter/ensemble_kalman_filter.py
Original file line number Diff line number Diff line change
Expand Up @@ -213,6 +213,9 @@ def main():

if show_animation:
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])

for i in range(len(z[:, 0])):
plt.plot([xTrue[0, 0], z[i, 2]], [xTrue[1, 0], z[i, 3]], "-k")
Expand Down
3 changes: 3 additions & 0 deletions Localization/extended_kalman_filter/extended_kalman_filter.py
Original file line number Diff line number Diff line change
Expand Up @@ -191,6 +191,9 @@ def main():

if show_animation:
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(hz[0, :], hz[1, :], ".g")
plt.plot(hxTrue[0, :].flatten(),
hxTrue[1, :].flatten(), "-b")
Expand Down
3 changes: 3 additions & 0 deletions Localization/histogram_filter/histogram_filter.py
Original file line number Diff line number Diff line change
Expand Up @@ -233,6 +233,9 @@ def main():

if show_animation:
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
draw_heat_map(grid_map.data, mx, my)
plt.plot(xTrue[0, :], xTrue[1, :], "xr")
plt.plot(RF_ID[:, 0], RF_ID[:, 1], ".k")
Expand Down
3 changes: 3 additions & 0 deletions Localization/particle_filter/particle_filter.py
Original file line number Diff line number Diff line change
Expand Up @@ -230,6 +230,9 @@ def main():

if show_animation:
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])

for i in range(len(z[:, 0])):
plt.plot([xTrue[0, 0], z[i, 1]], [xTrue[1, 0], z[i, 2]], "-k")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -240,6 +240,9 @@ def main():

if show_animation:
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(hz[0, :], hz[1, :], ".g")
plt.plot(np.array(hxTrue[0, :]).flatten(),
np.array(hxTrue[1, :]).flatten(), "-b")
Expand Down
3 changes: 3 additions & 0 deletions Mapping/circle_fitting/circle_fitting.py
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,9 @@ def main():

if show_animation: # pragma: no cover
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.axis("equal")
plt.plot(0.0, 0.0, "*r")
plot_circle(cx, cy, cr)
Expand Down
3 changes: 3 additions & 0 deletions Mapping/gaussian_grid_map/gaussian_grid_map.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,9 @@ def main():

if show_animation: # pragma: no cover
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
draw_heatmap(gmap, minx, maxx, miny, maxy, xyreso)
plt.plot(ox, oy, "xr")
plt.plot(0.0, 0.0, "ob")
Expand Down
4 changes: 3 additions & 1 deletion Mapping/kmeans_clustering/kmeans_clustering.py
Original file line number Diff line number Diff line change
Expand Up @@ -133,8 +133,10 @@ def main():
# for animation
if show_animation: # pragma: no cover
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
clusters.plot_cluster()

plt.plot(cx, cy, "or")
plt.xlim(-2.0, 10.0)
plt.ylim(-2.0, 10.0)
Expand Down
3 changes: 3 additions & 0 deletions Mapping/raycasting_grid_map/raycasting_grid_map.py
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,9 @@ def main():

if show_animation: # pragma: no cover
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
draw_heatmap(pmap, minx, maxx, miny, maxy, xyreso)
plt.plot(ox, oy, "xr")
plt.plot(0.0, 0.0, "ob")
Expand Down
3 changes: 3 additions & 0 deletions Mapping/rectangle_fitting/rectangle_fitting.py
Original file line number Diff line number Diff line change
Expand Up @@ -242,6 +242,9 @@ def main():

if show_animation: # pragma: no cover
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.axis("equal")
plt.plot(0.0, 0.0, "*r")
v1.plot()
Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/AStar/a_star.py
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,9 @@ def planning(self, sx, sy, gx, gy):
if show_animation: # pragma: no cover
plt.plot(self.calc_grid_position(current.x, self.minx),
self.calc_grid_position(current.y, self.miny), "xc")
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
if len(closed_set.keys()) % 10 == 0:
plt.pause(0.001)

Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py
Original file line number Diff line number Diff line change
Expand Up @@ -534,6 +534,9 @@ def update_graph(self):
def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None,
samples=None, start=None, end=None):
plt.clf()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
for rnd in samples:
if rnd is not None:
plt.plot(rnd[0], rnd[1], "^k")
Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/ClosedLoopRRTStar/pure_pursuit.py
Original file line number Diff line number Diff line change
Expand Up @@ -135,6 +135,9 @@ def closed_loop_prediction(cx, cy, cyaw, speed_profile, goal):

if target_ind % 1 == 0 and animation: # pragma: no cover
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(cx, cy, "-r", label="course")
plt.plot(x, y, "ob", label="trajectory")
plt.plot(cx[target_ind], cy[target_ind], "xg", label="target")
Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/Dijkstra/dijkstra.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,9 @@ def planning(self, sx, sy, gx, gy):
if show_animation: # pragma: no cover
plt.plot(self.calc_position(current.x, self.minx),
self.calc_position(current.y, self.miny), "xc")
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
if len(closedset.keys()) % 10 == 0:
plt.pause(0.001)

Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/DubinsPath/dubins_path_planning.py
Original file line number Diff line number Diff line change
Expand Up @@ -318,6 +318,9 @@ def test():

if show_animation:
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(px, py, label="final course " + str(mode))

# plotting
Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/DynamicWindowApproach/dynamic_window_approach.py
Original file line number Diff line number Diff line change
Expand Up @@ -268,6 +268,9 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle):

if show_animation:
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(predicted_trajectory[:, 0], predicted_trajectory[:, 1], "-g")
plt.plot(x[0], x[1], "xr")
plt.plot(goal[0], goal[1], "xb")
Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/Eta3SplinePath/eta3_spline_path.py
Original file line number Diff line number Diff line change
Expand Up @@ -213,6 +213,9 @@ def test1():
if show_animation:
# plot the path
plt.plot(pos[0, :], pos[1, :])
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.pause(1.0)

if show_animation:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -347,6 +347,9 @@ def main():

if show_animation: # pragma: no cover
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(tx, ty)
plt.plot(ob[:, 0], ob[:, 1], "xk")
plt.plot(path.x[1:], path.y[1:], "-or")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -213,6 +213,9 @@ def sweep_path_search(sweep_searcher, gmap, grid_search_animation=False):

if grid_search_animation:
fig, ax = plt.subplots()
# for stopping simulation with the esc key.
fig.canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])

while True:
cxind, cyind = sweep_searcher.move_target_grid(cxind, cyind, gmap)
Expand Down Expand Up @@ -266,6 +269,9 @@ def planning_animation(ox, oy, reso): # pragma: no cover
if do_animation:
for ipx, ipy in zip(px, py):
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(ox, oy, "-xb")
plt.plot(px, py, "-r")
plt.plot(ipx, ipy, "or")
Expand Down
5 changes: 4 additions & 1 deletion PathPlanning/HybridAStar/a_star.py
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,9 @@ def dp_planning(sx, sy, gx, gy, ox, oy, reso, rr):
# show graph
if show_animation: # pragma: no cover
plt.plot(current.x * reso, current.y * reso, "xc")
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
if len(closedset.keys()) % 10 == 0:
plt.pause(0.001)

Expand Down Expand Up @@ -228,4 +231,4 @@ def main():

if __name__ == '__main__':
show_animation = True
main()
main()
3 changes: 3 additions & 0 deletions PathPlanning/HybridAStar/hybrid_a_star.py
Original file line number Diff line number Diff line change
Expand Up @@ -327,6 +327,9 @@ def hybrid_a_star_planning(start, goal, ox, oy, xyreso, yawreso):

if show_animation: # pragma: no cover
plt.plot(current.xlist[-1], current.ylist[-1], "xc")
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
if len(closedList.keys()) % 10 == 0:
plt.pause(0.001)

Expand Down
4 changes: 3 additions & 1 deletion PathPlanning/InformedRRTStar/informed_rrt_star.py
Original file line number Diff line number Diff line change
Expand Up @@ -266,8 +266,10 @@ def get_final_course(self, lastIndex):
return path

def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, rnd=None):

plt.clf()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
if rnd is not None:
plt.plot(rnd[0], rnd[1], "^k")
if cBest != float('inf'):
Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/LQRPlanner/LQRplanner.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,9 @@ def lqr_planning(self, sx, sy, gx, gy, show_animation=True):

# animation
if show_animation: # pragma: no cover
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(sx, sy, "or")
plt.plot(gx, gy, "ob")
plt.plot(rx, ry, "-r")
Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/LQRRRTStar/lqr_rrt_star.py
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,9 @@ def planning(self, animation=True, search_until_max_iter=True):

def draw_graph(self, rnd=None):
plt.clf()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
if rnd is not None:
plt.plot(rnd.x, rnd.y, "^k")
for node in self.node_list:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,9 @@ def potential_field_planning(sx, sy, gx, gy, ox, oy, reso, rr):

if show_animation:
draw_heatmap(pmap)
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(ix, iy, "*k")
plt.plot(gix, giy, "*m")

Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py
Original file line number Diff line number Diff line change
Expand Up @@ -194,6 +194,9 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y):

# show graph
if show_animation and len(closedset.keys()) % 2 == 0:
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(current.x, current.y, "xg")
plt.pause(0.001)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,9 @@ def quintic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_
if show_animation: # pragma: no cover
for i, _ in enumerate(time):
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.grid(True)
plt.axis("equal")
plot_arrow(sx, sy, syaw)
Expand Down
3 changes: 3 additions & 0 deletions PathPlanning/RRT/rrt.py
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,9 @@ def get_random_node(self):

def draw_graph(self, rnd=None):
plt.clf()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
if rnd is not None:
plt.plot(rnd.x, rnd.y, "^k")
for node in self.node_list:
Expand Down
Loading

0 comments on commit ad5e1aa

Please sign in to comment.