Skip to content

Commit b4de4a1

Browse files
committed
code clean up
1 parent f9a4fc1 commit b4de4a1

File tree

12 files changed

+46
-264
lines changed

12 files changed

+46
-264
lines changed

Bipedal/bipedal_planner/bipedal_planner.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -52,10 +52,10 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False):
5252
self.ref_p = [] # reference footstep positions
5353
self.act_p = [] # actual footstep positions
5454

55-
px, py = 0., 0. # reference footstep position
55+
px, py = 0.0, 0.0 # reference footstep position
5656
px_star, py_star = px, py # modified footstep position
57-
xi, xi_dot, yi, yi_dot = 0., 0., 0.01, 0. # TODO yi should be set as +epsilon, set xi, yi as COM
58-
time = 0.
57+
xi, xi_dot, yi, yi_dot = 0.0, 0.0, 0.01, 0.0
58+
time = 0.0
5959
n = 0
6060
self.ref_p.append([px, py, 0])
6161
self.act_p.append([px, py, 0])

Mapping/kmeans_clustering/kmeans_clustering.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ def calc_association(cx, cy, clusters):
124124

125125
inds = []
126126

127-
for ic in range(len(cx)):
127+
for ic, _ in enumerate(cx):
128128
tcx = cx[ic]
129129
tcy = cy[ic]
130130

PathPlanning/AStar/a_star.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,7 @@ def a_star_planning(sx, sy, gx, gy, ox, oy, reso, rr):
8585
closedset[c_id] = current
8686

8787
# expand search grid based on motion model
88-
for i in range(len(motion)):
88+
for i, _ in enumerate(motion):
8989
node = Node(current.x + motion[i][0],
9090
current.y + motion[i][1],
9191
current.cost + motion[i][2], c_id)

PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py

+11-8
Original file line numberDiff line numberDiff line change
@@ -5,18 +5,21 @@
55
66
"""
77

8-
import sys
9-
sys.path.append("../ReedsSheppPath/")
10-
118
import random
129
import math
1310
import copy
1411
import numpy as np
1512
import pure_pursuit
1613
import matplotlib.pyplot as plt
1714

18-
import reeds_shepp_path_planning
19-
import unicycle_model
15+
import sys
16+
sys.path.append("../ReedsSheppPath/")
17+
18+
try:
19+
import reeds_shepp_path_planning
20+
import unicycle_model
21+
except:
22+
raise
2023

2124
show_animation = True
2225

@@ -130,8 +133,8 @@ def search_best_feasible_path(self, path_indexs):
130133
fy.append(self.end.y)
131134
fyaw.append(self.end.yaw)
132135
return True, fx, fy, fyaw, fv, ft, fa, fd
133-
else:
134-
return False, None, None, None, None, None, None, None
136+
137+
return False, None, None, None, None, None, None, None
135138

136139
def calc_tracking_path(self, path):
137140
path = np.array(path[::-1])
@@ -194,7 +197,7 @@ def check_tracking_path_is_feasible(self, path):
194197
return find_goal, x, y, yaw, v, t, a, d
195198

196199
def choose_parent(self, newNode, nearinds):
197-
if len(nearinds) == 0:
200+
if not nearinds:
198201
return newNode
199202

200203
dlist = []

PathPlanning/Dijkstra/dijkstra.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, reso, rr):
6767
closedset[c_id] = current
6868

6969
# expand search grid based on motion model
70-
for i in range(len(motion)):
70+
for i, _ in enumerate(motion):
7171
node = Node(current.x + motion[i][0], current.y + motion[i][1],
7272
current.cost + motion[i][2], c_id)
7373
n_id = calc_index(node, xw, minx, miny)

PathPlanning/Eta3SplinePath/eta3_spline_path.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -185,8 +185,8 @@ def calc_deriv(self, u, order=1):
185185
assert(order > 0 and order <= 2)
186186
if order == 1:
187187
return self.coeffs[:, 1:].dot(np.array([1, 2. * u, 3. * u**2, 4. * u**3, 5. * u**4, 6. * u**5, 7. * u**6]))
188-
else:
189-
return self.coeffs[:, 2:].dot(np.array([2, 6. * u, 12. * u**2, 20. * u**3, 30. * u**4, 42. * u**5]))
188+
189+
return self.coeffs[:, 2:].dot(np.array([2, 6. * u, 12. * u**2, 20. * u**3, 30. * u**4, 42. * u**5]))
190190

191191

192192
def test1():

PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -257,7 +257,7 @@ def check_collision(fp, ob):
257257
def check_paths(fplist, ob):
258258

259259
okind = []
260-
for i in range(len(fplist)):
260+
for i, _ in enumerate(fplist):
261261
if any([v > MAX_SPEED for v in fplist[i].s_d]): # Max speed check
262262
continue
263263
elif any([abs(a) > MAX_ACCEL for a in fplist[i].s_dd]): # Max accel check

PathPlanning/HybridAStar/hybrid_a_star.py

-222
This file was deleted.

PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py

+3-2
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0):
1818

1919

2020
def pi_2_pi(angle):
21-
return (angle + math.pi) % (2*math.pi) - math.pi
21+
return (angle + math.pi) % (2 * math.pi) - math.pi
2222

2323

2424
def update(state, v, delta, dt, L):
@@ -74,5 +74,6 @@ def generate_last_state(s, km, kf, k0):
7474

7575
state = State()
7676

77-
[update(state, v, ikp, dt, L) for ikp in kp]
77+
_ = [update(state, v, ikp, dt, L) for ikp in kp]
78+
7879
return state.x, state.y, state.yaw

PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py

+5-5
Original file line numberDiff line numberDiff line change
@@ -146,17 +146,17 @@ def quinic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_a
146146
break
147147

148148
if show_animation:
149-
for i in range(len(rx)):
149+
for i, _ in enumerate(rx):
150150
plt.cla()
151151
plt.grid(True)
152152
plt.axis("equal")
153153
plot_arrow(sx, sy, syaw)
154154
plot_arrow(gx, gy, gyaw)
155155
plot_arrow(rx[i], ry[i], ryaw[i])
156-
plt.title("Time[s]:" + str(time[i])[0:4] +
157-
" v[m/s]:" + str(rv[i])[0:4] +
158-
" a[m/ss]:" + str(ra[i])[0:4] +
159-
" jerk[m/sss]:" + str(rj[i])[0:4],
156+
plt.title("Time[s]:" + str(time[i])[0:4]
157+
+ " v[m/s]:" + str(rv[i])[0:4]
158+
+ " a[m/ss]:" + str(ra[i])[0:4]
159+
+ " jerk[m/sss]:" + str(rj[i])[0:4],
160160
)
161161
plt.pause(0.001)
162162

0 commit comments

Comments
 (0)