def process(args): '''process a set of files''' global slipmap, mosaic scan_count = 0 files = [] for a in args: if os.path.isdir(a): files.extend(glob.glob(os.path.join(a, '*.pgm'))) else: files.append(a) files.sort() num_files = len(files) print("num_files=%u" % num_files) region_count = 0 joes = [] if opts.mavlog: mpos = mav_position.MavInterpolator(gps_lag=opts.gps_lag) mpos.set_logfile(opts.mavlog) else: mpos = None if opts.boundary: boundary = cuav_util.polygon_load(opts.boundary) else: boundary = None if opts.mosaic: slipmap = mp_slipmap.MPSlipMap(service='GoogleSat', elevation=True, title='Map') icon = slipmap.icon('planetracker.png') slipmap.add_object(mp_slipmap.SlipIcon('plane', (0,0), icon, layer=3, rotation=0, follow=True, trail=mp_slipmap.SlipTrail())) C_params = cam_params.CameraParams(lens=opts.lens) path = os.path.join(os.path.dirname(os.path.realpath(__file__)), '..', '..', 'cuav', 'data', 'chameleon1_arecont0.json') C_params.load(path) mosaic = cuav_mosaic.Mosaic(slipmap, C=C_params) if boundary is not None: mosaic.set_boundary(boundary) if opts.joe: joes = cuav_util.polygon_load(opts.joe) if boundary: for i in range(len(joes)): joe = joes[i] if cuav_util.polygon_outside(joe, boundary): print("Error: joe outside boundary", joe) return icon = slipmap.icon('flag.png') slipmap.add_object(mp_slipmap.SlipIcon('joe%u' % i, (joe[0],joe[1]), icon, layer=4)) joelog = cuav_joe.JoeLog('joe.log') if opts.view: viewer = mp_image.MPImage(title='Image') frame_time = 0 for f in files: if mpos: frame_time = cuav_util.parse_frame_time(f) try: if opts.roll_stabilised: roll = 0 else: roll = None pos = mpos.position(frame_time, opts.max_deltat,roll=roll) slipmap.set_position('plane', (pos.lat, pos.lon), rotation=pos.yaw) except mav_position.MavInterpolatorException as e: print e pos = None else: pos = None # check for any events from the map if opts.mosaic: slipmap.check_events() mosaic.check_events() if f.endswith('.pgm'): pgm = cuav_util.PGM(f) im = pgm.array if pgm.eightbit: im_8bit = im else: im_8bit = numpy.zeros((960,1280,1),dtype='uint8') if opts.gamma != 0: scanner.gamma_correct(im, im_8bit, opts.gamma) else: scanner.reduce_depth(im, im_8bit) im_full = numpy.zeros((960,1280,3),dtype='uint8') scanner.debayer(im_8bit, im_full) im_640 = numpy.zeros((480,640,3),dtype='uint8') scanner.downsample(im_full, im_640) else: im_orig = cv.LoadImage(f) (w,h) = cuav_util.image_shape(im_orig) im_full = im_orig im_640 = cv.CreateImage((640, 480), 8, 3) cv.Resize(im_full, im_640, cv.CV_INTER_NN) im_640 = numpy.ascontiguousarray(cv.GetMat(im_640)) im_full = numpy.ascontiguousarray(cv.GetMat(im_full)) count = 0 total_time = 0 img_scan = im_640 t0=time.time() for i in range(opts.repeat): if opts.fullres: regions = scanner.scan(im_full) regions = cuav_region.RegionsConvert(regions, 1280, 960) else: regions = scanner.scan(img_scan) regions = cuav_region.RegionsConvert(regions) count += 1 t1=time.time() if opts.filter: regions = cuav_region.filter_regions(im_full, regions, frame_time=frame_time, min_score=opts.minscore, filter_type=opts.filter_type) scan_count += 1 # optionally link all the images with joe into a separate directory # for faster re-running of the test with just joe images if pos and opts.linkjoe and len(regions) > 0: cuav_util.mkdir_p(opts.linkjoe) if not cuav_util.polygon_outside((pos.lat, pos.lon), boundary): joepath = os.path.join(opts.linkjoe, os.path.basename(f)) if os.path.exists(joepath): os.unlink(joepath) os.symlink(f, joepath) if pos and len(regions) > 0: joelog.add_regions(frame_time, regions, pos, f, width=1280, height=960, altitude=opts.altitude) if boundary: regions = cuav_region.filter_boundary(regions, boundary, pos) region_count += len(regions) if opts.mosaic and len(regions) > 0: composite = cuav_mosaic.CompositeThumbnail(cv.GetImage(cv.fromarray(im_full)), regions) thumbs = cuav_mosaic.ExtractThumbs(composite, len(regions)) mosaic.add_regions(regions, thumbs, f, pos) if opts.compress: jpeg = scanner.jpeg_compress(im_full, opts.quality) jpeg_filename = f[:-4] + '.jpg' if os.path.exists(jpeg_filename): print('jpeg %s already exists' % jpeg_filename) continue chameleon.save_file(jpeg_filename, jpeg) if opts.view: if opts.fullres: img_view = im_full else: img_view = img_scan mat = cv.fromarray(img_view) for r in regions: (x1,y1,x2,y2) = r.tuple() (w,h) = cuav_util.image_shape(img_view) x1 = x1*w//1280 x2 = x2*w//1280 y1 = y1*h//960 y2 = y2*h//960 cv.Rectangle(mat, (max(x1-2,0),max(y1-2,0)), (x2+2,y2+2), (255,0,0), 2) cv.CvtColor(mat, mat, cv.CV_BGR2RGB) viewer.set_image(mat) total_time += (t1-t0) if t1 != t0: print('%s scan %.1f fps %u regions [%u/%u]' % ( f, count/total_time, region_count, scan_count, num_files))
def view_thread(): '''image viewing thread - this runs on the ground station''' from cuav.lib import cuav_mosaic state = mpstate.camera_state bsend = block_xmit.BlockSender(state.settings.gcs_view_port, bandwidth=state.settings.bandwidth) state.bsocket = MavSocket(mpstate.mav_master[0]) state.bsend2 = block_xmit.BlockSender(mss=96, sock=state.bsocket, dest_ip='mavlink', dest_port=0, backlog=5, debug=False) state.bsend2.set_bandwidth(state.settings.bandwidth2) view_window = False image_count = 0 thumb_count = 0 image_total_bytes = 0 jpeg_total_bytes = 0 thumb_total_bytes = 0 region_count = 0 mosaic = None thumbs_received = set() view_dir = os.path.join(state.camera_dir, "view") thumb_dir = os.path.join(state.camera_dir, "thumb") cuav_util.mkdir_p(view_dir) cuav_util.mkdir_p(thumb_dir) img_window = mp_image.MPImage(title='Camera') mpstate.console.set_status('Images', 'Images %u' % image_count, row=6) mpstate.console.set_status('Lost', 'Lost %u' % 0, row=6) mpstate.console.set_status('Regions', 'Regions %u' % region_count, row=6) mpstate.console.set_status('JPGSize', 'JPGSize %.0f' % 0.0, row=6) mpstate.console.set_status('XMITQ', 'XMITQ %.0f' % 0.0, row=6) mpstate.console.set_status('Thumbs', 'Thumbs %u' % thumb_count, row=7) mpstate.console.set_status('ThumbSize', 'ThumbSize %.0f' % 0.0, row=7) mpstate.console.set_status('ImageSize', 'ImageSize %.0f' % 0.0, row=7) ack_time = time.time() while not state.unload.wait(0.02): if state.viewing: tnow = time.time() if tnow - ack_time > 0.1: bsend.tick(packet_count=1000, max_queue=state.settings.maxqueue1) state.bsend2.tick(packet_count=1000, max_queue=state.settings.maxqueue2) if state.bsend_slave is not None: state.bsend_slave.tick(packet_count=1000) ack_time = tnow if not view_window: view_window = True mosaic = cuav_mosaic.Mosaic(slipmap=mpstate.map, C=state.c_params) if state.boundary_polygon is not None: mosaic.set_boundary(state.boundary_polygon) if mpstate.continue_mode: reload_mosaic(mosaic) # check for keyboard events mosaic.check_events() buf = bsend.recv(0) if buf is None: buf = state.bsend2.recv(0) if buf is None: continue try: obj = cPickle.loads(str(buf)) if obj == None: continue except Exception as e: continue if state.settings.gcs_slave is not None: if state.bsend_slave is None: state.bsend_slave = block_xmit.BlockSender(0, bandwidth=state.settings.bandwidth*10, debug=False) state.bsend_slave.send(buf, dest=(state.settings.gcs_slave, state.settings.gcs_view_port), priority=1) if isinstance(obj, ThumbPacket): # we've received a set of thumbnails from the plane for a positive hit if obj.frame_time in thumbs_received: continue thumbs_received.add(obj.frame_time) thumb_total_bytes += len(buf) # save the thumbnails thumb_filename = '%s/v%s.jpg' % (thumb_dir, cuav_util.frame_time(obj.frame_time)) chameleon.save_file(thumb_filename, obj.thumb) composite = cv.LoadImage(thumb_filename) thumbs = cuav_mosaic.ExtractThumbs(composite, len(obj.regions)) # log the joe positions filename = '%s/v%s.jpg' % (view_dir, cuav_util.frame_time(obj.frame_time)) pos = obj.pos log_joe_position(pos, obj.frame_time, obj.regions, filename, thumb_filename) # update the mosaic and map mosaic.set_brightness(state.settings.brightness) mosaic.add_regions(obj.regions, thumbs, filename, pos=pos) # update console display region_count += len(obj.regions) state.frame_loss = obj.frame_loss state.xmit_queue = obj.xmit_queue thumb_count += 1 mpstate.console.set_status('Lost', 'Lost %u' % state.frame_loss) mpstate.console.set_status('Regions', 'Regions %u' % region_count) mpstate.console.set_status('XMITQ', 'XMITQ %.0f' % state.xmit_queue) mpstate.console.set_status('Thumbs', 'Thumbs %u' % thumb_count) mpstate.console.set_status('ThumbSize', 'ThumbSize %.0f' % (thumb_total_bytes/thumb_count)) if isinstance(obj, ImagePacket): # we have an image from the plane image_total_bytes += len(buf) state.xmit_queue = obj.xmit_queue mpstate.console.set_status('XMITQ', 'XMITQ %.0f' % state.xmit_queue) # save it to disk filename = '%s/v%s.jpg' % (view_dir, cuav_util.frame_time(obj.frame_time)) chameleon.save_file(filename, obj.jpeg) img = cv.LoadImage(filename) if img.width == 1280: display_img = cv.CreateImage((640, 480), 8, 3) cv.Resize(img, display_img) else: display_img = img mosaic.add_image(obj.frame_time, filename, obj.pos) cv.ConvertScale(display_img, display_img, scale=state.settings.brightness) img_window.set_image(display_img, bgr=True) # update console image_count += 1 jpeg_total_bytes += len(obj.jpeg) state.jpeg_size = 0.95 * state.jpeg_size + 0.05 * len(obj.jpeg) mpstate.console.set_status('Images', 'Images %u' % image_count) mpstate.console.set_status('JPGSize', 'JPG Size %.0f' % (jpeg_total_bytes/image_count)) mpstate.console.set_status('ImageSize', 'ImageSize %.0f' % (image_total_bytes/image_count)) if isinstance(obj, CommandResponse): print('REMOTE: %s' % obj.response) else: if view_window: view_window = False
def process(args): '''process a set of files''' global slipmap, mosaic scan_count = 0 files = [] if os.path.isdir(args.directory): files.extend(file_list(args.directory, ['jpg', 'pgm', 'png'])) else: if args.directory.find('*') != -1: files.extend(glob.glob(args.directory)) else: files.append(args.directory) files.sort() num_files = len(files) print("num_files=%u" % num_files) region_count = 0 slipmap = mp_slipmap.MPSlipMap(service=args.service, elevation=True, title='Map') icon = slipmap.icon('redplane.png') slipmap.add_object( mp_slipmap.SlipIcon('plane', (0, 0), icon, layer=3, rotation=0, follow=True, trail=mp_slipmap.SlipTrail())) for flag in args.flag: a = flag.split(',') lat = a[0] lon = a[1] icon = 'flag.png' if len(a) > 2: icon = a[2] + '.png' icon = slipmap.icon(icon) slipmap.add_object( mp_slipmap.SlipIcon('icon - %s' % str(flag), (float(lat), float(lon)), icon, layer=3, rotation=0, follow=False)) if args.mission: from pymavlink import mavwp wp = mavwp.MAVWPLoader() wp.load(args.mission.name) plist = wp.polygon_list() if len(plist) > 0: for i in range(len(plist)): slipmap.add_object( mp_slipmap.SlipPolygon('Mission-%s-%u' % (args.mission.name, i), plist[i], layer='Mission', linewidth=2, colour=(255, 255, 255))) if args.mavlog: mpos = mav_position.MavInterpolator() mpos.set_logfile(args.mavlog.name) else: mpos = None if args.gammalog is not None: gamma = parse_gamma_log(args.gammalog) else: gamma = None if args.kmzlog: kmzpos = mav_position.KmlPosition(args.kmzlog.name) else: kmzpos = None if args.triggerlog: triggerpos = mav_position.TriggerPosition(args.triggerlog.name) else: triggerpos = None # create a simple lens model using the focal length if args.camera_params: C_params = cam_params.CameraParams.fromfile(args.camera_params.name) else: C_params = cam_params.CameraParams(lens=args.lens, sensorwidth=args.sensorwidth, xresolution=args.xresolution, yresolution=args.yresolution) if args.target: target = args.target.split(',') else: target = [0, 0, 0] camera_settings = MPSettings([ MPSetting('roll_stabilised', bool, args.roll_stabilised, 'Roll Stabilised'), MPSetting('altitude', int, args.altitude, 'Altitude', range=(0, 10000), increment=1), MPSetting( 'minalt', int, 30, 'MinAltitude', range=(0, 10000), increment=1), MPSetting('mpp100', float, 0.0977, 'MPPat100m', range=(0, 10000), increment=0.001), MPSetting('rotate180', bool, args.rotate_180, 'rotate180'), MPSetting('filter_type', str, 'compactness', 'Filter Type', choice=['simple', 'compactness']), MPSetting('target_lattitude', float, float(target[0]), 'target latitude', increment=1.0e-7), MPSetting('target_longitude', float, float(target[1]), 'target longitude', increment=1.0e-7), MPSetting('target_radius', float, float(target[2]), 'target radius', increment=1), MPSetting('quality', int, 75, 'Compression Quality', range=(1, 100), increment=1), MPSetting('thumbsize', int, args.thumbsize, 'Thumbnail Size', range=(10, 200), increment=1), MPSetting('minscore', int, args.minscore, 'Min Score', range=(0, 1000), increment=1, tab='Scoring'), MPSetting('brightness', float, 1.0, 'Display Brightness', range=(0.1, 10), increment=0.1, digits=2, tab='Display'), ], title='Camera Settings') image_settings = MPSettings([ MPSetting('MinRegionArea', float, 0.05, range=(0, 100), increment=0.05, digits=2, tab='Image Processing'), MPSetting('MaxRegionArea', float, 4.0, range=(0, 100), increment=0.1, digits=1), MPSetting('MinRegionSize', float, 0.02, range=(0, 100), increment=0.05, digits=2), MPSetting('MaxRegionSize', float, 3.0, range=(0, 100), increment=0.1, digits=1), MPSetting('MaxRarityPct', float, 0.02, range=(0, 100), increment=0.01, digits=2), MPSetting('RegionMergeSize', float, 1.0, range=(0, 100), increment=0.1, digits=1), MPSetting('BlueEmphasis', bool, args.blue_emphasis), MPSetting('SaveIntermediate', bool, args.debug) ], title='Image Settings') mosaic = cuav_mosaic.Mosaic(slipmap, C=C_params, camera_settings=camera_settings, image_settings=image_settings, start_menu=True, classify=args.categories, thumb_size=args.mosaic_thumbsize) joelog = cuav_joe.JoeLog(None) if args.view: viewer = mp_image.MPImage(title='Image', can_zoom=True, can_drag=True) start_time = time.time() for f in files: if not mosaic.started(): print("Waiting for startup") if args.start: mosaic.has_started = True while not mosaic.started(): mosaic.check_events() time.sleep(0.01) if mpos: # get the position by interpolating telemetry data from the MAVLink log file # this assumes that the filename contains the timestamp if gamma is not None: frame_time = parse_gamma_time(f, gamma) else: frame_time = cuav_util.parse_frame_time(f) frame_time += args.time_offset if camera_settings.roll_stabilised: roll = 0 else: roll = None try: pos = mpos.position(frame_time, roll=roll) except Exception: print("No position available for %s" % frame_time) # skip this frame continue elif kmzpos is not None: pos = kmzpos.position(f) elif triggerpos is not None: pos = triggerpos.position(f) else: # get the position using EXIF data pos = mav_position.exif_position(f) pos.time += args.time_offset # update the plane icon on the map if pos is not None: slipmap.set_position('plane', (pos.lat, pos.lon), rotation=pos.yaw) if camera_settings.altitude > 0: pos.altitude = camera_settings.altitude # check for any events from the map slipmap.check_events() mosaic.check_events() im_orig = cuav_util.LoadImage(f, rotate180=camera_settings.rotate180) if im_orig is None: continue (w, h) = cuav_util.image_shape(im_orig) if False: im_640 = cv.CreateImage((640, 480), 8, 3) cv.Resize(im_full, im_640, cv.CV_INTER_NN) im_640 = numpy.ascontiguousarray(cv.GetMat(im_640)) im_full = im_orig im_full = numpy.ascontiguousarray(cv.GetMat(im_full)) count = 0 total_time = 0 t0 = time.time() img_scan = im_full scan_parms = {} for name in image_settings.list(): scan_parms[name] = image_settings.get(name) scan_parms['SaveIntermediate'] = float(scan_parms['SaveIntermediate']) scan_parms['BlueEmphasis'] = float(scan_parms['BlueEmphasis']) if pos is not None: (sw, sh) = cuav_util.image_shape(img_scan) altitude = pos.altitude if altitude < camera_settings.minalt: altitude = camera_settings.minalt scan_parms[ 'MetersPerPixel'] = camera_settings.mpp100 * altitude / 100.0 regions = scanner.scan(img_scan, scan_parms) else: regions = scanner.scan(img_scan) regions = cuav_region.RegionsConvert(regions, cuav_util.image_shape(img_scan), cuav_util.image_shape(im_full)) count += 1 t1 = time.time() frame_time = pos.time if pos: for r in regions: r.latlon = cuav_util.gps_position_from_image_region( r, pos, w, h, altitude=altitude, C=C_params) if camera_settings.target_radius > 0 and pos is not None: regions = cuav_region.filter_radius( regions, (camera_settings.target_lattitude, camera_settings.target_longitude), camera_settings.target_radius) regions = cuav_region.filter_regions( im_full, regions, frame_time=frame_time, min_score=camera_settings.minscore, filter_type=camera_settings.filter_type) scan_count += 1 if pos and len(regions) > 0: altitude = camera_settings.altitude if altitude <= 0: altitude = None joelog.add_regions(frame_time, regions, pos, f, width=w, height=h, altitude=altitude) mosaic.add_image(pos.time, f, pos) region_count += len(regions) if len(regions) > 0: composite = cuav_mosaic.CompositeThumbnail( cv.GetImage(cv.fromarray(im_full)), regions) thumbs = cuav_mosaic.ExtractThumbs(composite, len(regions)) mosaic.add_regions(regions, thumbs, f, pos) if args.view: img_view = img_scan (wview, hview) = cuav_util.image_shape(img_view) mat = cv.fromarray(img_view) for r in regions: r.draw_rectangle(mat, (255, 0, 0)) cv.CvtColor(mat, mat, cv.CV_BGR2RGB) viewer.set_image(mat) viewer.set_title('Image: ' + os.path.basename(f)) if args.saveview: cv.CvtColor(mat, mat, cv.CV_RGB2BGR) cv.SaveImage('view-' + os.path.basename(f), mat) total_time += (t1 - t0) if t1 != t0: print('%s scan %.1f fps %u regions [%u/%u]' % (os.path.basename(f), count / total_time, region_count, scan_count, num_files)) #raw_input("hit ENTER when ready") print("All images processed (%u seconds)" % (time.time() - start_time)) while True: # check for any events from the map slipmap.check_events() mosaic.check_events() time.sleep(0.2)
def view_threadfunc(self): '''image viewing thread - this runs on the ground station''' self.start_gcs_bsend() self.image_count = 0 self.thumb_count = 0 self.image_total_bytes = 0 #jpeg_total_bytes = 0 self.thumb_total_bytes = 0 self.region_count = 0 self.mosaic = None self.thumbs_received = set() # the downloaded thumbs and views are stored in a temp dir self.view_dir = os.path.join(self.camera_dir, "view") #self.thumb_dir = os.path.join(self.camera_dir, "thumb") cuav_util.mkdir_p(self.view_dir) #cuav_util.mkdir_p(self.thumb_dir) self.console.set_status('Images', 'Images %u' % self.image_count, row=6) self.console.set_status('Regions', 'Regions %u' % self.region_count, row=6) self.console.set_status('Thumbs', 'Thumbs %u' % self.thumb_count, row=7) self.console.set_status('ThumbSize', 'ThumbSize %.0f' % 0.0, row=7) self.console.set_status('BX1', 'BX1 --', row=7) self.console.set_status('BX2', 'BX2 --', row=7) self.console.set_status('BX3', 'BX3 --', row=7) # give time for maps to init time.sleep(3) map2 = self.module("map2") map3 = self.module("map3") if map2: search_map = map2.map if map3: lz_map = map3.map self.mosaic = cuav_mosaic.Mosaic( slipmap=self.mpstate.map, C=self.c_params, camera_settings=None, image_settings=None, thumb_size=self.camera_settings.mosaic_thumbsize, search_map=search_map, lz_map=lz_map) while not self.unload_event.wait(0.05): if self.boundary_polygon is not None: self.mosaic.set_boundary(self.boundary_polygon) if self.continue_mode: self.reload_mosaic(self.mosaic) # check for keyboard events self.mosaic.check_events() self.check_requested_images(self.mosaic) #check for any new packets for bsnd in self.bsend: bsnd.tick(packet_count=1000, max_queue=self.camera_settings.maxqueue) self.check_commands(bsnd) if self.msend is not None: self.msend.tick(packet_count=1000, max_queue=self.camera_settings.maxqueue) self.check_commands(self.msend) self.send_heartbeats() #ensure the mosiac is closed at end of thread if self.mosaic.image_mosaic: self.mosaic.image_mosaic.terminate()
def process(args): '''process a set of files''' global slipmap, mosaic scan_count = 0 files = [] for a in args: if os.path.isdir(a): files.extend(file_list(a, ['jpg', 'pgm', 'png'])) else: if a.find('*') != -1: files.extend(glob.glob(a)) else: files.append(a) files.sort() num_files = len(files) print("num_files=%u" % num_files) region_count = 0 slipmap = mp_slipmap.MPSlipMap(service=opts.service, elevation=True, title='Map') icon = slipmap.icon('redplane.png') slipmap.add_object( mp_slipmap.SlipIcon('plane', (0, 0), icon, layer=3, rotation=0, follow=True, trail=mp_slipmap.SlipTrail())) if opts.mission: from pymavlink import mavwp wp = mavwp.MAVWPLoader() wp.load(opts.mission) boundary = wp.polygon() slipmap.add_object( mp_slipmap.SlipPolygon('mission', boundary, layer=1, linewidth=1, colour=(255, 255, 255))) if opts.mavlog: mpos = mav_position.MavInterpolator() mpos.set_logfile(opts.mavlog) else: mpos = None if opts.kmzlog: kmzpos = mav_position.KmlPosition(opts.kmzlog) else: kmzpos = None if opts.triggerlog: triggerpos = mav_position.TriggerPosition(opts.triggerlog) else: triggerpos = None # create a simple lens model using the focal length C_params = cam_params.CameraParams(lens=opts.lens, sensorwidth=opts.sensorwidth) if opts.camera_params: C_params.load(opts.camera_params) camera_settings = MPSettings([ MPSetting('roll_stabilised', bool, True, 'Roll Stabilised'), MPSetting( 'altitude', int, 0, 'Altitude', range=(0, 10000), increment=1), MPSetting('filter_type', str, 'simple', 'Filter Type', choice=['simple', 'compactness']), MPSetting('fullres', bool, False, 'Full Resolution'), MPSetting('quality', int, 75, 'Compression Quality', range=(1, 100), increment=1), MPSetting('thumbsize', int, 60, 'Thumbnail Size', range=(10, 200), increment=1), MPSetting('minscore', int, 75, 'Min Score', range=(0, 1000), increment=1, tab='Scoring'), MPSetting('brightness', float, 1.0, 'Display Brightness', range=(0.1, 10), increment=0.1, digits=2, tab='Display') ], title='Camera Settings') image_settings = MPSettings([ MPSetting('MinRegionArea', float, 0.15, range=(0, 100), increment=0.05, digits=2, tab='Image Processing'), MPSetting('MaxRegionArea', float, 2.0, range=(0, 100), increment=0.1, digits=1), MPSetting('MinRegionSize', float, 0.1, range=(0, 100), increment=0.05, digits=2), MPSetting( 'MaxRegionSize', float, 2, range=(0, 100), increment=0.1, digits=1), MPSetting('MaxRarityPct', float, 0.02, range=(0, 100), increment=0.01, digits=2), MPSetting('RegionMergeSize', float, 3.0, range=(0, 100), increment=0.1, digits=1), MPSetting('SaveIntermediate', bool, False) ], title='Image Settings') mosaic = cuav_mosaic.Mosaic(slipmap, C=C_params, camera_settings=camera_settings, image_settings=image_settings, start_menu=True) joelog = cuav_joe.JoeLog(None) if opts.view: viewer = mp_image.MPImage(title='Image', can_zoom=True, can_drag=True) if camera_settings.filter_type == 'compactness': calculate_compactness = True print("Using compactness filter") else: calculate_compactness = False for f in files: if not mosaic.started(): print("Waiting for startup") while not mosaic.started(): mosaic.check_events() time.sleep(0.01) if mpos: # get the position by interpolating telemetry data from the MAVLink log file # this assumes that the filename contains the timestamp frame_time = cuav_util.parse_frame_time(f) + opts.time_offset if camera_settings.roll_stabilised: roll = 0 else: roll = None try: pos = mpos.position(frame_time, roll=roll) except Exception: print("No position available for %s" % frame_time) # skip this frame continue elif kmzpos is not None: pos = kmzpos.position(f) elif triggerpos is not None: pos = triggerpos.position(f) else: # get the position using EXIF data pos = mav_position.exif_position(f) pos.time += opts.time_offset # update the plane icon on the map if pos is not None: slipmap.set_position('plane', (pos.lat, pos.lon), rotation=pos.yaw) if camera_settings.altitude > 0: pos.altitude = camera_settings.altitude # check for any events from the map slipmap.check_events() mosaic.check_events() im_orig = cuav_util.LoadImage(f) (w, h) = cuav_util.image_shape(im_orig) if not opts.camera_params: C_params.set_resolution(w, h) im_full = im_orig im_640 = cv.CreateImage((640, 480), 8, 3) cv.Resize(im_full, im_640, cv.CV_INTER_NN) im_640 = numpy.ascontiguousarray(cv.GetMat(im_640)) im_full = numpy.ascontiguousarray(cv.GetMat(im_full)) count = 0 total_time = 0 t0 = time.time() if camera_settings.fullres: img_scan = im_full else: img_scan = im_640 scan_parms = {} for name in image_settings.list(): scan_parms[name] = image_settings.get(name) scan_parms['SaveIntermediate'] = float(scan_parms['SaveIntermediate']) if pos is not None: (sw, sh) = cuav_util.image_shape(img_scan) mpp = cuav_util.meters_per_pixel(pos, C=C_params) if mpp is not None: scan_parms['MetersPerPixel'] = mpp * (w / float(sw)) regions = scanner.scan(img_scan, scan_parms) else: regions = scanner.scan(img_scan) regions = cuav_region.RegionsConvert(regions, cuav_util.image_shape(img_scan), cuav_util.image_shape(im_full), calculate_compactness) count += 1 t1 = time.time() frame_time = pos.time regions = cuav_region.filter_regions( im_full, regions, frame_time=frame_time, min_score=camera_settings.minscore, filter_type=camera_settings.filter_type) scan_count += 1 mosaic.add_image(pos.time, f, pos) if pos and len(regions) > 0: altitude = camera_settings.altitude if altitude <= 0: altitude = None joelog.add_regions(frame_time, regions, pos, f, width=w, height=h, altitude=altitude) region_count += len(regions) if len(regions) > 0: composite = cuav_mosaic.CompositeThumbnail( cv.GetImage(cv.fromarray(im_full)), regions) thumbs = cuav_mosaic.ExtractThumbs(composite, len(regions)) mosaic.add_regions(regions, thumbs, f, pos) if opts.view: img_view = img_scan (wview, hview) = cuav_util.image_shape(img_view) mat = cv.fromarray(img_view) for r in regions: r.draw_rectangle(mat, (255, 0, 0)) cv.CvtColor(mat, mat, cv.CV_BGR2RGB) viewer.set_image(mat) viewer.set_title('Image: ' + os.path.basename(f)) total_time += (t1 - t0) if t1 != t0: print('%s scan %.1f fps %u regions [%u/%u]' % (os.path.basename(f), count / total_time, region_count, scan_count, num_files))
def process(args): '''process a set of files''' global slipmap, mosaic scan_count = 0 files = scan_image_directory(args.imagedir) files.sort() num_files = len(files) print("num_files=%u" % num_files) region_count = 0 joes = [] if args.mavlog: mpos = mav_position.MavInterpolator(gps_lag=args.gps_lag) mpos.set_logfile(args.mavlog) else: mpos = None if args.boundary: boundary = cuav_util.polygon_load(args.boundary) else: boundary = None if args.mosaic: slipmap = mp_slipmap.MPSlipMap(service='GoogleSat', elevation=True, title='Map') icon = slipmap.icon('redplane.png') slipmap.add_object(mp_slipmap.SlipIcon('plane', (0,0), icon, layer=3, rotation=0, follow=True, trail=mp_slipmap.SlipTrail())) if args.camera_params: C_params = cam_params.CameraParams.fromfile(args.camera_params.name) else: im_orig = cv2.imread(files[0]) (w,h) = cuav_util.image_shape(im_orig) C_params = cam_params.CameraParams(lens=args.lens, sensorwidth=args.sensorwidth, xresolution=w, yresolution=h) mosaic = cuav_mosaic.Mosaic(slipmap, C=C_params) if boundary is not None: mosaic.set_boundary(boundary) if args.joe: joes = cuav_util.polygon_load(args.joe) if boundary: for i in range(len(joes)): joe = joes[i] if cuav_util.polygon_outside(joe, boundary): print("Error: joe outside boundary", joe) return icon = slipmap.icon('flag.png') slipmap.add_object(mp_slipmap.SlipIcon('joe%u' % i, (joe[0],joe[1]), icon, layer=4)) joelog = cuav_joe.JoeLog('joe.log') if args.view: viewer = mp_image.MPImage(title='Image') frame_time = 0 scan_parms = { 'MinRegionArea' : args.min_region_area, 'MaxRegionArea' : args.max_region_area, 'MinRegionSize' : args.min_region_size, 'MaxRegionSize' : args.max_region_size, 'MaxRarityPct' : args.max_rarity_pct, 'RegionMergeSize' : args.region_merge, 'SaveIntermediate' : float(0), #'SaveIntermediate' : float(args.debug), 'MetersPerPixel' : args.meters_per_pixel100 * args.altitude / 100.0 } filenum = 0 for f in files: filenum += 1 if mpos: frame_time = cuav_util.parse_frame_time(f) try: if args.roll_stabilised: roll = 0 else: roll = None pos = mpos.position(frame_time, args.max_deltat,roll=roll) slipmap.set_position('plane', (pos.lat, pos.lon), rotation=pos.yaw) except mav_position.MavInterpolatorException as e: print(e) pos = None else: pos = None # check for any events from the map if args.mosaic: slipmap.check_events() mosaic.check_events() im_orig = cv2.imread(f) (w,h) = cuav_util.image_shape(im_orig) im_full = im_orig im_half = cv2.resize(im_orig, (0,0), fx=0.5, fy=0.5) im_half = numpy.ascontiguousarray(im_half) im_full = numpy.ascontiguousarray(im_full) count = 0 total_time = 0 if args.fullres: img_scan = im_full else: img_scan = im_half t0=time.time() for i in range(args.repeat): regions = scanner.scan(img_scan, scan_parms) regions = cuav_region.RegionsConvert(regions, cuav_util.image_shape(img_scan), cuav_util.image_shape(im_full)) count += 1 t1=time.time() if args.filter: regions = cuav_region.filter_regions(im_full, regions, min_score=args.minscore, filter_type=args.filter_type) if len(regions) > 0 and args.debug: composite = cuav_region.CompositeThumbnail(im_full, regions, thumb_size=args.thumb_size) thumbs = cuav_mosaic.ExtractThumbs(composite, len(regions)) thumb_num = 0 for thumb in thumbs: print("thumb %u score %f" % (thumb_num, regions[thumb_num].score)) cv2.imwrite('%u_thumb%u.jpg' % (filenum,thumb_num), thumb) thumb_num += 1 scan_count += 1 # optionally link all the images with joe into a separate directory # for faster re-running of the test with just joe images if pos and args.linkjoe and len(regions) > 0: cuav_util.mkdir_p(args.linkjoe) if not cuav_util.polygon_outside((pos.lat, pos.lon), boundary): joepath = os.path.join(args.linkjoe, os.path.basename(f)) if os.path.exists(joepath): os.unlink(joepath) os.symlink(f, joepath) if pos and len(regions) > 0: joelog.add_regions(frame_time, regions, pos, f, width=w, height=h, altitude=args.altitude, C=C_params) if boundary: regions = cuav_region.filter_boundary(regions, boundary, pos) region_count += len(regions) if args.mosaic and len(regions) > 0 and pos: composite = cuav_region.CompositeThumbnail(im_full, regions) thumbs = cuav_mosaic.ExtractThumbs(composite, len(regions)) mosaic.add_regions(regions, thumbs, f, pos) if args.view: if args.fullres: img_view = im_full else: img_view = img_scan #mat = cv.fromarray(img_view) for r in regions: r.draw_rectangle(img_view, colour=(255,0,0), linewidth=min(max(w/600,1),3), offset=max(w/200,1)) img_view = cv2.cvtColor(img_view, cv2.COLOR_BGR2RGB) viewer.set_image(img_view) total_time += (t1-t0) if t1 != t0: print('%s scan %.1f fps %u regions [%u/%u]' % ( f, count/total_time, region_count, scan_count, num_files))
def test_Mosaic(): #slipmap = mp_slipmap.MPSlipMap(service='GoogleSat', elevation=True, title='Map') #mocked_slipmap.return_value = 1 #monkeypatch.setattr('slipmap', lambda x: 1) mocked_slipmap = mock.MagicMock(return_value=1) C_params = CameraParams(lens=4.0, sensorwidth=5.0, xresolution=1280, yresolution=960) mosaic = cuav_mosaic.Mosaic(mocked_slipmap, C=C_params) mosaic.set_mosaic_size((200, 200)) assert mosaic.mosaic.shape == (175, 175, 3) f = os.path.join(os.getcwd(), 'tests', 'testdata', 'raw2016111223465120Z.png') img = cv2.imread(f) pos = mav_position.MavPosition(-30, 145, 34.56, 20, -56.67, 345, frame_time=1478994408.76) regions = [] regions.append(cuav_region.Region(1020, 658, 1050, 678, (30, 30), scan_score=20)) regions.append(cuav_region.Region(30, 54, 50, 74, (20, 20), scan_score=15)) regions.append(cuav_region.Region(30, 54, 55, 79, (25, 25), scan_score=10)) for i in range(40): regions.append(cuav_region.Region(200, 600, 220, 620, (20, 20), scan_score=45)) composite = cuav_region.CompositeThumbnail(img, regions) thumbs = cuav_mosaic.ExtractThumbs(composite, len(regions)) mosaic.add_regions(regions, thumbs, f, pos) mosaic.add_image(1478994408.76, f, pos) mosaic.show_region(0) mosaic.view_imagefile(f) assert mosaic.find_image_idx(f) == 0 mosaic.view_imagefile_by_idx(0) mocked_key = mock.MagicMock(return_value=1) mocked_key.objkey = "region 1" assert mosaic.show_selected(mocked_key) == True mosaic.show_closest((-30, 145), mocked_key) mosaic.view_image.terminate() #mosaic.map_menu_callback #mosaic.map_callback OBC_boundary = cuav_util.polygon_load(os.path.join(os.getcwd(), 'tests', 'testdata', 'OBC_boundary.txt')) mosaic.set_boundary(OBC_boundary) mosaic.change_page(1) mosaic.hide_page() assert len(mosaic.regions_sorted) == 25 mosaic.unhide_all() assert len(mosaic.regions_sorted) == 43 for i in ['Score', 'ScoreReverse', 'Distinctiveness', 'Whiteness', 'Time']: mosaic.sort_type = i mosaic.re_sort() #mosaic.menu_event assert mosaic.started() == True mosaic.popup_show_image(mosaic.regions[2]) mosaic.popup_fetch_image(mosaic.regions[2], 'fetchImageFull') assert len(mosaic.get_image_requests()) == 1 mosaic.view_image.terminate() #mosaic.menu_event_view mocked_pos = mock.MagicMock(return_value=1) mocked_pos.x = 10 mocked_pos.y = 10 assert mosaic.pos_to_region(mocked_pos) == mosaic.regions[0] assert mosaic.objkey_to_region(mocked_key) == mosaic.regions[1] #mosaic.mouse_event #mosaic.mouse_event_view mosaic.key_event(1) assert mosaic.region_on_page(2, 0) == True assert mosaic.region_on_page(2000, 20) == False mosaic.mouse_region = mosaic.regions[0] mosaic.display_mosaic_region(0) mosaic.redisplay_mosaic() assert mosaic.make_thumb(img, regions[0], 8).shape == (8, 8, 3) assert mosaic.make_thumb(img, regions[0], 30).shape == (30, 30, 3) mosaic.tag_image(1478994408.76) #mosaic.check_events mosaic.image_mosaic.terminate()
def process(args): '''process a set of files''' global slipmap, mosaic scan_count = 0 files = [] for a in args: if os.path.isdir(a): files.extend(file_list(a, ['jpg', 'pgm', 'png'])) else: if a.find('*') != -1: files.extend(glob.glob(a)) else: files.append(a) files.sort() num_files = len(files) print("num_files=%u" % num_files) region_count = 0 slipmap = mp_slipmap.MPSlipMap(service=opts.service, elevation=True, title='Map') icon = slipmap.icon('redplane.png') slipmap.add_object( mp_slipmap.SlipIcon('plane', (0, 0), icon, layer=3, rotation=0, follow=True, trail=mp_slipmap.SlipTrail())) if opts.mission: from pymavlink import mavwp wp = mavwp.MAVWPLoader() wp.load(opts.mission) boundary = wp.polygon() slipmap.add_object( mp_slipmap.SlipPolygon('mission', boundary, layer=1, linewidth=1, colour=(255, 255, 255))) if opts.mavlog: mpos = mav_position.MavInterpolator() mpos.set_logfile(opts.mavlog) else: mpos = None if opts.kmzlog: kmzpos = mav_position.KmlPosition(opts.kmzlog) else: kmzpos = None if opts.triggerlog: triggerpos = mav_position.TriggerPosition(opts.triggerlog) else: triggerpos = None # create a simple lens model using the focal length C_params = cam_params.CameraParams(lens=opts.lens, sensorwidth=opts.sensorwidth) if opts.camera_params: C_params.load(opts.camera_params) mosaic = cuav_mosaic.Mosaic(slipmap, C=C_params) joelog = cuav_joe.JoeLog(None) if opts.view: viewer = mp_image.MPImage(title='Image', can_zoom=True, can_drag=True) scan_parms = { 'MinRegionArea': opts.min_region_area, 'MaxRegionArea': opts.max_region_area, 'MinRegionSize': opts.min_region_size, 'MaxRegionSize': opts.max_region_size, 'MaxRarityPct': opts.max_rarity_pct, 'RegionMergeSize': opts.region_merge } for f in files: if mpos: # get the position by interpolating telemetry data from the MAVLink log file # this assumes that the filename contains the timestamp frame_time = cuav_util.parse_frame_time(f) + opts.time_offset if opts.roll_stabilised: roll = 0 else: roll = None try: pos = mpos.position(frame_time, roll=roll) except Exception: print("No position available for %s" % frame_time) # skip this frame continue elif kmzpos is not None: pos = kmzpos.position(f) elif triggerpos is not None: pos = triggerpos.position(f) else: # get the position using EXIF data pos = mav_position.exif_position(f) pos.time += opts.time_offset # update the plane icon on the map if pos is not None: slipmap.set_position('plane', (pos.lat, pos.lon), rotation=pos.yaw) # check for any events from the map slipmap.check_events() mosaic.check_events() im_orig = cuav_util.LoadImage(f) (w, h) = cuav_util.image_shape(im_orig) if not opts.camera_params: C_params.set_resolution(w, h) im_full = im_orig im_640 = cv.CreateImage((640, 480), 8, 3) cv.Resize(im_full, im_640, cv.CV_INTER_NN) im_640 = numpy.ascontiguousarray(cv.GetMat(im_640)) im_full = numpy.ascontiguousarray(cv.GetMat(im_full)) count = 0 total_time = 0 t0 = time.time() if opts.fullres: img_scan = im_full else: img_scan = im_640 if pos is not None: (sw, sh) = cuav_util.image_shape(img_scan) mpp = cuav_util.meters_per_pixel(pos, C=C_params) if mpp is not None: scan_parms['MetersPerPixel'] = mpp * (w / float(sw)) regions = scanner.scan(img_scan, scan_parms) else: regions = scanner.scan(img_scan) regions = cuav_region.RegionsConvert(regions, cuav_util.image_shape(img_scan), cuav_util.image_shape(im_full)) count += 1 t1 = time.time() frame_time = pos.time regions = cuav_region.filter_regions(im_full, regions, frame_time=frame_time, min_score=opts.minscore, filter_type=opts.filter_type) scan_count += 1 mosaic.add_image(pos.time, f, pos) if pos and len(regions) > 0: joelog.add_regions(frame_time, regions, pos, f, width=w, height=h, altitude=opts.altitude) region_count += len(regions) if len(regions) > 0: composite = cuav_mosaic.CompositeThumbnail( cv.GetImage(cv.fromarray(im_full)), regions) thumbs = cuav_mosaic.ExtractThumbs(composite, len(regions)) mosaic.add_regions(regions, thumbs, f, pos) if opts.view: img_view = img_scan (wview, hview) = cuav_util.image_shape(img_view) mat = cv.fromarray(img_view) for r in regions: r.draw_rectangle(mat, (255, 0, 0)) cv.CvtColor(mat, mat, cv.CV_BGR2RGB) viewer.set_image(mat) viewer.set_title('Image: ' + os.path.basename(f)) total_time += (t1 - t0) if t1 != t0: print('%s scan %.1f fps %u regions [%u/%u]' % (os.path.basename(f), count / total_time, region_count, scan_count, num_files))