def show_image(view, selected_image, im_rgb, fname): '''show a image view''' view.set_title("%s %s" % (selected_image, fname)) if selected_image == "original": view.set_image(im_rgb) return im = cuav_util.LoadImage(selected_image + ".pnm") im_numpy = numpy.ascontiguousarray(cv.GetMat(im)) im_rgb = cv.fromarray(im_numpy) view.set_image(im_rgb)
def load_fake_image(filename): print "Loading mock file: %s" % filename if filename.endswith('.pgm'): return cuav_util.PGM(filename) img = cuav_util.LoadImage(filename) array = numpy.ascontiguousarray(cv.GetMat(img)) grey = numpy.zeros((image_height, image_width), dtype='uint8') scanner.rebayer(array, grey) return array
def process(args): '''process a set of files''' files = [] if os.path.isdir(args.directory): files.extend(glob.glob(os.path.join(args.directory, '*.pgm'))) else: if args.directory.find('*') != -1: files.extend(glob.glob(args.directory)) else: files.append(args.directory) files.sort() for f in files: im_orig = cuav_util.LoadImage(f) if not args.output_directory: outdir = os.path.dirname(f) else: outdir = args.output_directory basename = os.path.basename(f)[:-4] new_name = os.path.join(outdir, basename + '.' + args.format) print("Creating %s" % new_name) cv.SaveImage(new_name, im_orig)
def load_image(filename): print "Loading file: %s" % filename img = cuav_util.LoadImage(filename) array = numpy.ascontiguousarray(cv.GetMat(img)) return array
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 load_image(filename): img = cuav_util.LoadImage(filename=filename) return numpy.asarray(cv.GetMat(img))
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 spectrum(): array = numpy.zeros((480, 640, 3), dtype='uint8') for y in range(480): for x in range(640): h = int((255 * x) / 640) s = 255 v = int((255 * y) / 480) array[y, x] = (h, s, v) hsv = cv.GetImage(cv.fromarray(array)) return hsv if len(args) == 0: hsv = spectrum() rgb = cv.CreateImage(cv.GetSize(hsv), 8, 3) cv.CvtColor(hsv, rgb, cv.CV_HSV2RGB) else: img = cuav_util.LoadImage(args[0]) (w, h) = cv.GetSize(img) img2 = cv.CreateImage((w / 2, h / 2), 8, 3) cv.Resize(img, img2) hsv = cv.CreateImage((w / 2, h / 2), 8, 3) cv.CvtColor(img2, hsv, cv.CV_RGB2HSV) rgb = cv.CreateImage(cv.GetSize(hsv), 8, 3) cv.CvtColor(hsv, rgb, cv.CV_HSV2RGB) cv.ShowImage('HSV', rgb) cv.SetMouseCallback('HSV', mouse_event, (rgb, hsv)) cuav_util.cv_wait_quit()
def process(args): '''process a file''' file_index = 0 if os.path.isdir(args[0]): files = file_list(args[0], ['jpg', 'pgm', 'png']) else: files = args fname = files[file_index] settings = MPSettings([ MPSetting('MetersPerPixel', float, 0.2, range=(0, 10), increment=0.01, digits=2, tab='Image Processing'), MPSetting('MinRegionArea', float, 0.15, range=(0, 100), increment=0.05, digits=2), 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('minscore', int, 0, 'Min Score', range=(0, 1000), increment=1, tab='Scoring'), MPSetting('filter_type', str, 'simple', 'Filter Type', choice=['simple', 'compactness']), MPSetting('brightness', float, 1.0, 'Display Brightness', range=(0.1, 10), increment=0.1, digits=2, tab='Display') ], title='Settings') menu = MPMenuSubMenu( 'View', items=[ MPMenuItem('Original Image', 'Original Image', 'originalImage'), MPMenuItem('Unquantised Image', 'Unquantised Image', 'unquantisedImage'), MPMenuItem('Thresholded Image', 'Thresholded Image', 'thresholdedImage'), MPMenuItem('Neighbours Image', 'Neighbours Image', 'neighboursImage'), MPMenuItem('Regions Image', 'Regions Image', 'regionsImage'), MPMenuItem('Prune Large Image', 'Prune Large Image', 'prunelargeImage'), MPMenuItem('Merged Image', 'Merged Large', 'mergedImage'), MPMenuItem('Pruned Image', 'Pruned Image', 'prunedImage'), MPMenuItem('Fit Window', 'Fit Window', 'fitWindow'), MPMenuItem('Full Zoom', 'Full Zoom', 'fullSize'), MPMenuItem('Next Image', 'Next Image', 'nextImage'), MPMenuItem('Previous Image', 'Previous Image', 'previousImage') ]) im_orig = cuav_util.LoadImage(fname) im_numpy = numpy.ascontiguousarray(cv.GetMat(im_orig)) im_rgb = cv.fromarray(im_numpy) cv.CvtColor(im_rgb, im_rgb, cv.CV_BGR2RGB) # create the various views view = mp_image.MPImage(title='FullImage', can_zoom=True, can_drag=True) view.set_popup_menu(menu) dlg = wxsettings.WXSettings(settings) selected_image = "original" while dlg.is_alive() and view.is_alive(): last_change = settings.last_change() scan_parms = { 'MinRegionArea': settings.MinRegionArea, 'MaxRegionArea': settings.MaxRegionArea, 'MinRegionSize': settings.MinRegionSize, 'MaxRegionSize': settings.MaxRegionSize, 'MaxRarityPct': settings.MaxRarityPct, 'RegionMergeSize': settings.RegionMergeSize, 'SaveIntermediate': 1.0, 'MetersPerPixel': settings.MetersPerPixel } t0 = time.time() regions = scanner.scan(im_numpy, scan_parms) regions = cuav_region.RegionsConvert(regions, cuav_util.image_shape(im_orig), cuav_util.image_shape(im_orig), False) t1 = time.time() print("Processing %s took %.2f seconds" % (fname, t1 - t0)) show_image(view, selected_image, im_rgb, fname) while last_change == settings.last_change() and dlg.is_alive(): new_index = file_index for event in view.events(): if isinstance(event, MPMenuItem): if event.returnkey == 'nextImage': new_index = (file_index + 1) % len(files) elif event.returnkey == 'previousImage': new_index = (file_index - 1) % len(files) elif event.returnkey.endswith("Image"): selected_image = event.returnkey[:-5] show_image(view, selected_image, im_rgb, fname) if new_index != file_index: file_index = new_index fname = files[file_index] im_orig = cuav_util.LoadImage(fname) im_numpy = numpy.ascontiguousarray(cv.GetMat(im_orig)) im_rgb = cv.fromarray(im_numpy) cv.CvtColor(im_rgb, im_rgb, cv.CV_BGR2RGB) break time.sleep(0.1)
from cuav.lib import cuav_mosaic from optparse import OptionParser parser = OptionParser("cuav_joe.py [options]") parser.add_option("--minscore", type='int', default=1000, help="min score") (opts, args) = parser.parse_args() sm = mp_slipmap.MPSlipMap(lat=-26.6360, lon=151.8436, elevation=True, service='GoogleSat') joelog = JoeIterator(sys.argv[1]) tidx = 0 thumb_filename = None for joe in joelog: thumb = cuav_util.LoadImage(joe.thumb_filename) if thumb_filename != joe.thumb_filename: tidx = 0 else: tidx += 1 (w, h) = cuav_util.image_shape(thumb) count = w // h thumbs = cuav_mosaic.ExtractThumbs(thumb, count) r = getattr(joe, 'r', None) if r is not None and r.score > opts.minscore: print joe sm.add_object( mp_slipmap.SlipThumbnail("time %u" % joe.frame_time, joe.latlon, img=thumbs[tidx], layer=2,
def load_image(filename): raw = cuav_util.LoadImage(filename) return numpy.asarray(cv.GetMat(raw))
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))