-
Notifications
You must be signed in to change notification settings - Fork 5
/
viewer.py
408 lines (359 loc) · 12.8 KB
/
viewer.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
#!/usr/bin/env python
"""
simple tool for robot path analysis
viewer.py <filename> [--startIndex=<num>] [<scale> [<tile size>]]
"""
import sys
import os, math, pygame
from pygame.locals import *
# ------- video loading ----------
import pave
import cv2
# hack for RR only
from rr_drone import processFrame
printPosition = True
printEncoders = True
size = 1200, 660
offset = 150, 150
absOffset = 0, 0 # offset of original (x,y) coordinate system (Robotour stromovka = 1049800.66, 5580126.84 )
sample_color = (255,0,0)
sample_size = 20
track_color = (0,255,0)
track_size = 2
tile_size = 0.5
def deg(degAngle): return math.pi*degAngle/180.0
def draw(surface, samples):
for s in samples:
surface.fill(sample_color, (to_px(s[0]), to_px(s[1]), sample_size, sample_size))
def to_px(x): return int(x*150*scale)
def _scr(x,y): return (to_px(x)+offset[0], size[1]-to_px(y)-offset[1])
def scr(x,y): return _scr(x-absOffset[0], y-absOffset[1])
def scr1( point ) : return scr( point[0], point[1] )
#-------------------------------------------------
def getCombinedPose( pose, sensorPose ):
x = pose[0] + sensorPose[0] * math.cos( pose[2] ) - sensorPose[1] * math.sin( pose[2] )
y = pose[1] + sensorPose[0] * math.sin( pose[2] ) + sensorPose[1] * math.cos( pose[2] )
heading = sensorPose[2] + pose[2]
return (x, y, heading)
def loadVideoFrame( filename ):
assert ":" in filename, filename
frameNumber = int(filename.split(':')[-1])
filename = ":".join(filename.split(":")[:-1])
f = open(filename,"rb")
proc = pave.PaVE()
while True:
packet = f.read(10000)
if (packet) == 0:
break
proc.append( packet )
header,payload = proc.extract()
while payload:
if pave.isIFrame( header ) and pave.frameNumber( header ) == frameNumber:
tmpFile = open( "tmp.bin", "wb" )
tmpFile.write( payload )
tmpFile.flush()
tmpFile.close()
cap = cv2.VideoCapture( "tmp.bin" )
ret, frame = cap.read()
processFrame( frame, debug=True ) # hack!!
cv2.imwrite( "test.jpg", frame ) # dirty solution how to get image from OpenCV to Pygame :(
return pygame.image.load( "test.jpg" )
header,payload = proc.extract()
return None # frame not found
def loadData( filename ):
# geometry = ( ( -0.02, 0.04, deg(90) ), ( -0.02, -0.04, deg(-90) ) )
# geometry = ( ( -0.09, 0.14, deg(90) ), ( -0.09, -0.14, deg(-90) ) )
# geometry = ( ( -0.09, 0.14, deg(90) ), ( -0.09, -0.14, deg(-90) ),
# ( 0.05, 0.10, deg(0) ), ( 0.05, -0.10, deg(0) ) )
map = []
geometry = []
posesSet = []
poses = []
scans = []
image = None
video = None
camdir = None
compass = None
readingMap = False
for line in open( filename ):
arr = line.rstrip().split()
if not line.rstrip():
continue
if arr[0] == "Map":
readingMap = True
elif arr[0] == "Poses":
readingMap = False
if poses:
posesSet.append( (poses, scans, image, camdir, compass) )
poses = []
scans = []
image = None
camdir = None
compass = None
elif arr[0] == "Compass":
readingMap = False
compass = float(arr[1])
elif arr[0] == "Geometry":
geometry = []
tmp = arr[1:]
while len( tmp ) > 0:
geometry.append( (float(tmp[0]), float(tmp[1]), float(tmp[2])) )
tmp = tmp[3:]
elif arr[0] == "Ranger":
readingMap = False
i = 0
for a in arr[4:]:
scans.append( ( getCombinedPose( (float(arr[1]), float(arr[2]), float(arr[3])), geometry[i] ), float(a)) )
i += 1
elif arr[0] == "Beacon":
assert( int(arr[1]) == 1 )
index = len(arr)>4 and int(arr[4]) or 0
if len(arr) == 7:
scans.append( ( ( float(arr[2]), float(arr[3]), 0.0 ), -1.5, [int(c) for c in arr[-3:]]) ) # color param
else:
scans.append( ( ( float(arr[2]), float(arr[3]), 0.0 ), -1.0-index/10.0) )
elif arr[0] == "Puck":
assert( int(arr[1]) == 1 )
scans.append( ( ( float(arr[2]), float(arr[3]), 0.0 ), -2.0) )
elif arr[0] == "RefPose":
assert( int(arr[1]) == 1 )
scans.append( ( ( float(arr[2]), float(arr[3]), 0.0 ), -3.0) )
elif arr[0] == "Image":
image = arr[1]
elif arr[0] == "Video":
video = arr[1]
elif arr[0] == "Frame":
assert video != None
image = video + ":" + arr[1] # frame number
elif arr[0] == "ImageResult":
try:
camdir = float(arr[1])
except: #it cannot be interpreted as a direction
pass
else:
if readingMap:
map.append( ((float(arr[0]), float(arr[1])), (float(arr[2]),float(arr[3]))) )
else:
poses.append( (float(arr[0]), float(arr[1]), float(arr[2])) )
posesSet.append( (poses,scans,image,camdir, compass) )
return posesSet, map
def drawPoses( foreground, poses ):
d = 0.3
for (x,y,heading) in poses:
pygame.draw.circle( foreground, (0,0,255), scr(x,y),5 )
pygame.draw.line( foreground, (255,255,0), scr(x,y), scr(x+d*math.cos(heading),y+d*math.sin(heading)),5)
def drawCompass( foreground, scanArr ):
if scanArr[4]:
x,y,heading = scanArr[0][0]
heading = scanArr[4]
d = 0.4
pygame.draw.line( foreground, (0,0,255), scr(x,y), scr(x+d*math.cos(heading),y+d*math.sin(heading)),5)
def drawScans( foreground, scans, shouldDrawSensors, shouldDrawBeacons ):
for row in scans:
color = None
if len(row) == 2:
((x,y,heading),range) = row
else:
((x,y,heading),range, color) = row
if range >= 0:
if range > 0:
if shouldDrawSensors:
col = (0,255,0)
ptSize = 6
if range > 2.0:
col = (0,100,0)
ptSize = 3
pygame.draw.circle( foreground, col, scr(x+range*math.cos(heading),y+range*math.sin(heading)), ptSize )
pygame.draw.circle( foreground, (255,0,0), scr(x,y), 4 )
elif range > -1.99:
# beacons (not nice)
if shouldDrawBeacons:
if color == None:
pygame.draw.circle( foreground, (255,0,int((-1-range)*255*3.3)), scr(x,y), 6 )
else:
pygame.draw.circle( foreground, color, scr(x,y), 6 )
elif range > -2.5:
# pucks (not nice2)
pygame.draw.circle( foreground, (255,0,168), scr(x,y), 3 )
else:
# ref MCL pose (not nice3)
pygame.draw.circle( foreground, (255,0,0), scr(x,y), 1 )
def drawMap( foreground, map ):
for m in map:
pygame.draw.line( foreground, (0,255,255), scr1(m[0]), scr1(m[1]),5)
def drawImage( foreground, imgFileName, camdir ):
if imgFileName:
# imgFileName = 'D:\\md\\hg\\eduro-logs\\100619-rychnov\\pes1\\cam100619_145404_000.jpg'
if "video_rec" in imgFileName:
camera = loadVideoFrame( imgFileName )
else:
camera = pygame.image.load( imgFileName ).convert()
cameraView = pygame.transform.scale( camera, (320, 180) )
if camdir is not None:
color = (0xFF, 0x00, 0x00)
start_pos = (160, 180)
length = 80
end_pos = (160 - length * math.sin(camdir), 180 - length * math.cos(camdir))
width = 2
pygame.draw.line(cameraView, color, start_pos, end_pos, width)
foreground.blit( cameraView, (size[0]-320,0) )
def drawTiles( background ):
background.fill((35, 35, 35))
tile_size_px = to_px(tile_size)
for x in range(0, size[0] + tile_size_px, tile_size_px):
for y in range(0, size[1] + tile_size_px, tile_size_px):
if (x / tile_size_px) % 2 == (y / tile_size_px) % 2:
background.fill((235, 235, 235), Rect(x, size[1] - y, tile_size_px, tile_size_px))
# draw scale
pygame.draw.line( background, (255,0,0), (20,size[1]-20), (20+to_px(1.0),size[1]-20),3)
pygame.draw.line( background, (255,0,0), (20,size[1]-10), (20,size[1]-30),1)
pygame.draw.line( background, (255,0,0), (20+to_px(1.0),size[1]-10), (20+to_px(1.0),size[1]-30),1)
def main( filename, scale = 1.0, startIndex = None ):
# load pygame
pygame.init()
os.environ['SDL_VIDEO_CENTERED'] = '1'
#screen = pygame.display.set_mode(size, NOFRAME, 0)
screen = pygame.display.set_mode(size)
# create backgroud
background = pygame.Surface(screen.get_size())
drawTiles(background)
# create foreground
foreground = pygame.Surface(screen.get_size())
foreground.set_colorkey((0,0,0))
index = 0
# display everything
screen.blit(background, (0, 0))
screen.blit(foreground, (0, 0))
pygame.display.flip()
pygame.event.set_blocked(MOUSEMOTION) # keep our queue cleaner
pygame.key.set_repeat ( 200, 20 )
shouldDrawTiles = True
shouldDrawMap = True
shouldDrawSensors = False
shouldDrawBeacons = False
shouldRefreshNow = False
posesScanSet, map = loadData( filename )
drawPoses( foreground, posesScanSet[0][0] )
drawScans( foreground, posesScanSet[0][1], shouldDrawSensors, shouldDrawBeacons )
screen.blit(background, (0, 0))
screen.blit(foreground, (0, 0))
pygame.display.set_caption("Viewer init ...")
pygame.display.flip()
global absOffset
if startIndex != None:
index = startIndex
if index < len(posesScanSet):
# move robot into center
pose = posesScanSet[index][0][0]
absOffset = pose[:2]
else:
# skip first non-moving part
index = 0
for s in posesScanSet:
pose = s[0][0]
index += 1
if math.fabs(pose[0])+math.fabs(pose[1]) > 1.0:
absOffset = pose[:2]
break
if index >= len(posesScanSet):
index = len(posesScanSet) - 1
print index, len(posesScanSet), absOffset
imgFileName = None
lastImgFileName = None
while 1:
if imgFileName:
t = str(imgFileName)+' ***'
lastImgFileName = imgFileName
else:
t = str(lastImgFileName)
pygame.display.set_caption("Index: %d, sensors %s, img %s" % (index, shouldDrawSensors and "on" or "off", t) )
shouldRefreshNow = False
event = pygame.event.wait()
if event.type == QUIT: return
if event.type == KEYDOWN:
if event.key in (K_ESCAPE,K_q): return
if event.key == K_p:
if index + 1 < len( posesScanSet ):
index += 1
if event.key == K_o:
if index + 10 < len( posesScanSet ):
index += 10
if event.key == K_i:
if index > 0:
index -= 1
if event.key == K_0:
index = 0
if event.key == K_9:
index = len( posesScanSet ) - 1
if event.key == K_m:
shouldDrawMap = not shouldDrawMap;
if event.key == K_s:
shouldDrawSensors = not shouldDrawSensors;
if event.key == K_b:
shouldDrawBeacons = not shouldDrawBeacons;
if event.key == K_RIGHT:
globals()['offset'] = (offset[0]+150, offset[1])
shouldRefreshNow = True
if event.key == K_LEFT:
globals()['offset'] = (offset[0]-150, offset[1])
shouldRefreshNow = True
if event.key == K_UP:
globals()['offset'] = (offset[0], offset[1]+150)
shouldRefreshNow = True
if event.key == K_DOWN:
globals()['offset'] = (offset[0], offset[1]-150)
shouldRefreshNow = True
if event.key == K_PLUS or event.unicode == '+':
globals()['scale'] *= 2.0
globals()['tile_size'] /= 2.0
shouldDrawTiles = shouldDrawMap = shouldDrawSensors = shouldDrawBeacons = True
shouldRefreshNow = True
if event.key == K_MINUS or event.unicode == '-':
globals()['scale'] /= 2.0
globals()['tile_size'] *= 2.0
shouldDrawTiles = shouldDrawMap = shouldDrawSensors = shouldDrawBeacons = True
shouldRefreshNow = True
def has_image(k):
return bool(posesScanSet[k][2])
if has_image(index) or shouldRefreshNow:
foreground.fill( (0,0,0) )
refreshed_since = index
if shouldRefreshNow:
while refreshed_since > 0:
if has_image(refreshed_since):
break
refreshed_since -= 1
for i in range(refreshed_since, index + 1):
drawPoses( foreground, posesScanSet[i][0] )
drawCompass( foreground, posesScanSet[i] )
drawScans( foreground, posesScanSet[i][1], shouldDrawSensors, shouldDrawBeacons )
drawImage( foreground, posesScanSet[i][2], posesScanSet[i][3] )
imgFileName = posesScanSet[i][2]
if event.key == K_a:
foreground.fill( (0,0,0) )
for (p,s,i,camdir,comp) in posesScanSet:
drawScans( foreground, s, shouldDrawSensors, shouldDrawBeacons )
if shouldDrawTiles:
drawTiles(background)
if shouldDrawMap:
drawMap( foreground, map )
screen.blit(background, (0, 0))
screen.blit(foreground, (0, 0))
pygame.display.flip()
def usage():
print __doc__
if __name__ == "__main__":
if len(sys.argv) < 2:
usage()
sys.exit(2)
scale = 1.0
args = sys.argv[:]
startIndex = None
if len(args) > 2 and args[2].startswith("--startIndex"):
startIndex = int(args[2].split('=')[1])
args = args[:2]+args[3:]
if len(args) > 2:
scale = float( args[2] )
if len(args) > 3:
tile_size = float( args[3] )
main(args[1], scale=scale, startIndex=startIndex)