mirror of
https://github.com/AtsushiSakai/PythonRobotics.git
synced 2026-01-13 07:27:56 -05:00
Merge pull request #48 from daniel-s-ingram/master
Fixed issue with float index for Python 2
This commit is contained in:
@@ -50,7 +50,7 @@ def atan_zero_to_twopi(y, x):
|
||||
|
||||
def precasting(minx, miny, xw, yw, xyreso, yawreso):
|
||||
|
||||
precast = [[] for i in range(round((math.pi * 2.0) / yawreso) + 1)]
|
||||
precast = [[] for i in range(int(round((math.pi * 2.0) / yawreso)) + 1)]
|
||||
|
||||
for ix in range(xw):
|
||||
for iy in range(yw):
|
||||
@@ -59,7 +59,7 @@ def precasting(minx, miny, xw, yw, xyreso, yawreso):
|
||||
|
||||
d = math.sqrt(px**2 + py**2)
|
||||
angle = atan_zero_to_twopi(py, px)
|
||||
angleid = math.floor(angle / yawreso)
|
||||
angleid = int(math.floor(angle / yawreso))
|
||||
|
||||
pc = precastDB()
|
||||
|
||||
@@ -87,7 +87,7 @@ def generate_ray_casting_grid_map(ox, oy, xyreso, yawreso):
|
||||
|
||||
d = math.sqrt(x**2 + y**2)
|
||||
angle = atan_zero_to_twopi(y, x)
|
||||
angleid = math.floor(angle / yawreso)
|
||||
angleid = int(math.floor(angle / yawreso))
|
||||
|
||||
gridlist = precast[angleid]
|
||||
|
||||
|
||||
@@ -25,8 +25,8 @@ def calc_potential_field(gx, gy, ox, oy, reso, rr):
|
||||
miny = min(oy) - AREA_WIDTH / 2.0
|
||||
maxx = max(ox) + AREA_WIDTH / 2.0
|
||||
maxy = max(oy) + AREA_WIDTH / 2.0
|
||||
xw = round((maxx - minx) / reso)
|
||||
yw = round((maxy - miny) / reso)
|
||||
xw = int(round((maxx - minx) / reso))
|
||||
yw = int(round((maxy - miny) / reso))
|
||||
|
||||
# calc each potential
|
||||
pmap = [[0.0 for i in range(yw)] for i in range(xw)]
|
||||
@@ -107,8 +107,8 @@ def potential_field_planning(sx, sy, gx, gy, ox, oy, reso, rr):
|
||||
minp = float("inf")
|
||||
minix, miniy = -1, -1
|
||||
for i in range(len(motion)):
|
||||
inx = ix + motion[i][0]
|
||||
iny = iy + motion[i][1]
|
||||
inx = int(ix + motion[i][0])
|
||||
iny = int(iy + motion[i][1])
|
||||
if inx >= len(pmap) or iny >= len(pmap[0]):
|
||||
p = float("inf") # outside area
|
||||
else:
|
||||
|
||||
Reference in New Issue
Block a user