def add_regions(self, frame_time, regions, pos, image_filename, thumb_filename=None, width=1280, height=960, altitude=None): '''add a set of regions to the log, applying geo-referencing. Add latlon attribute to regions ''' ret = [] for r in regions: if r.latlon is None: latlon = cuav_util.gps_position_from_image_region( r, pos, width, height, altitude=altitude) else: # the plane already added latlon latlon = r.latlon if latlon is not None: r.latlon = latlon self.add(latlon, frame_time, r, pos, image_filename, thumb_filename) return ret
def add_regions( self, frame_time, regions, pos, image_filename, thumb_filename=None, width=1280, height=960, altitude=None ): """add a set of regions to the log, applying geo-referencing. Add latlon attribute to regions """ ret = [] for r in regions: if r.latlon is None: latlon = cuav_util.gps_position_from_image_region(r, pos, width, height, altitude=altitude) else: # the plane already added latlon latlon = r.latlon if latlon is not None: r.latlon = latlon self.add(latlon, frame_time, r, pos, image_filename, thumb_filename) return ret
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()) ) for flag in opts.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 opts.mission: from pymavlink import mavwp wp = mavwp.MAVWPLoader() wp.load(opts.mission) plist = wp.polygon_list() if len(plist) > 0: for i in range(len(plist)): slipmap.add_object( mp_slipmap.SlipPolygon( "Mission-%s-%u" % (opts.mission, i), plist[i], layer="Mission", linewidth=2, colour=(255, 255, 255), ) ) if opts.mavlog: mpos = mav_position.MavInterpolator() mpos.set_logfile(opts.mavlog) else: mpos = None if opts.gammalog is not None: gamma = parse_gamma_log(opts.gammalog) else: gamma = 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) if opts.target: target = opts.target.split(",") else: target = [0, 0, 0] camera_settings = MPSettings( [ MPSetting("roll_stabilised", bool, opts.roll_stabilised, "Roll Stabilised"), MPSetting("altitude", int, opts.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, opts.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, opts.thumbsize, "Thumbnail Size", range=(10, 200), increment=1), MPSetting("minscore", int, opts.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, opts.blue_emphasis), MPSetting("SaveIntermediate", bool, opts.debug), ], title="Image Settings", ) mosaic = cuav_mosaic.Mosaic( slipmap, C=C_params, camera_settings=camera_settings, image_settings=image_settings, start_menu=True, classify=opts.categories, thumb_size=opts.mosaic_thumbsize, ) joelog = cuav_joe.JoeLog(None) if opts.view: viewer = mp_image.MPImage(title="Image", can_zoom=True, can_drag=True) 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 if gamma is not None: frame_time = parse_gamma_time(f, gamma) else: frame_time = cuav_util.parse_frame_time(f) frame_time += 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, rotate180=camera_settings.rotate180) if im_orig is None: continue (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() 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) 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 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)) if opts.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") while True: # check for any events from the map slipmap.check_events() mosaic.check_events() time.sleep(0.2)
def scan_threadfunc(self): '''image scanning thread''' while not self.unload_event.wait(0.05): if self.scan_queue.empty(): continue (frame_time,im) = self.scan_queue.get() scan_parms = {} for name in self.image_settings.list(): scan_parms[name] = self.image_settings.get(name) scan_parms['BlueEmphasis'] = float(self.camera_settings.blue_emphasis) if self.terrain_alt is not None: altitude = self.terrain_alt if altitude < self.camera_settings.minalt: altitude = self.camera_settings.minalt scan_parms['MetersPerPixel'] = cuav_util.pixel_width(altitude, self.c_params.xresolution, self.c_params.lens, self.c_params.sensorwidth) t1 = time.time() try: img_scan = cv2.imread(im, -1) except Exception: continue if img_scan is None: continue (h, w) = img_scan.shape[:2] if self.camera_settings.rotate180: M = cv2.getRotationMatrix2D(center, angle180, scale) img_scan = cv2.warpAffine(img_scan, M, (w, h)) im_numpy = numpy.ascontiguousarray(img_scan) regions = scanner.scan(im_numpy, scan_parms) regions = cuav_region.RegionsConvert(regions, cuav_util.image_shape(img_scan), cuav_util.image_shape(img_scan)) t2 = time.time() self.scan_fps = 1.0 / (t2-t1) self.scan_count += 1 regions = cuav_region.filter_regions(img_scan, regions, min_score=self.camera_settings.minscore, filter_type=self.camera_settings.filter_type) self.region_count += len(regions) # possibly send a preview image self.send_preview(img_scan) if self.camera_settings.roll_stabilised: roll=0 else: roll=None pos = self.get_plane_position(frame_time, roll=roll) if pos is not None: self.posmapping[str(frame_time)] = pos # this adds the latlon field to the regions (georeferencing) for r in regions: r.latlon = cuav_util.gps_position_from_image_region(r, pos, w, h, altitude=None, C=self.c_params) if self.joelog: self.log_joe_position(pos, frame_time, regions) # filter out any regions outside the target radius if self.camera_settings.target_radius > 0 and pos is not None: regions = cuav_region.filter_radius(regions, (self.camera_settings.target_latitude, self.camera_settings.target_longitude), self.camera_settings.target_radius) # filter out any regions outside the boundary if self.boundary_polygon: regions = cuav_region.filter_boundary(regions, self.boundary_polygon, pos) #filter by minscore regions = cuav_region.filter_regions(img_scan, regions, min_score=self.camera_settings.minscore, filter_type=self.camera_settings.filter_type) high_score = 1 for r in regions: if r.score > high_score: high_score = r.score if len(regions) > 0 and pos is not None: for r in regions: self.lz.checkaddregion(r, pos) try: lzresult = self.lz.calclandingzone() except Exception as ex: print("calclandingzone failed: ", ex) continue if lzresult: self.transmit_queue.put((lzresult, 100000, None)) if self.msend: self.transmit_queue.put((lzresult, 100000, 'msend')) if len(regions) > 0 and self.camera_settings.transmit: # send a region message with thumbnails to the ground station thumb_img = cuav_region.CompositeThumbnail(img_scan, regions, thumb_size=self.camera_settings.thumbsize) encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 90] (result, thumb) = cv2.imencode('.jpg', thumb_img, encode_param) pkt = cuav_command.ThumbPacket(frame_time, regions, thumb, pos) if self.transmit_queue.qsize() < 100: self.transmit_queue.put((pkt, None, None)) if self.msend is not None and high_score >= self.camera_settings.m_minscore: self.transmit_queue.put((pkt, None, 'msend')) else: self.send_message("Warning: image Tx queue too long") print("Warning: image Tx queue too long")
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 scan_threadfunc(self): '''image scanning thread''' while not self.unload_event.wait(0.05): if self.scan_queue.empty(): continue (frame_time, im) = self.scan_queue.get() scan_parms = {} for name in self.image_settings.list(): scan_parms[name] = self.image_settings.get(name) scan_parms['BlueEmphasis'] = float( self.camera_settings.blue_emphasis) if self.terrain_alt is not None: altitude = self.terrain_alt if altitude < self.camera_settings.minalt: altitude = self.camera_settings.minalt scan_parms['MetersPerPixel'] = cuav_util.pixel_width( altitude, self.c_params.xresolution, self.c_params.lens, self.c_params.sensorwidth) t1 = time.time() try: img_scan = cv2.imread(im, -1) except Exception: continue if img_scan is None: continue (h, w) = img_scan.shape[:2] if self.camera_settings.rotate180: M = cv2.getRotationMatrix2D(center, angle180, scale) img_scan = cv2.warpAffine(img_scan, M, (w, h)) im_numpy = numpy.ascontiguousarray(img_scan) regions = scanner.scan(im_numpy, scan_parms) regions = cuav_region.RegionsConvert( regions, cuav_util.image_shape(img_scan), cuav_util.image_shape(img_scan)) t2 = time.time() self.scan_fps = 1.0 / (t2 - t1) self.scan_count += 1 regions = cuav_region.filter_regions( img_scan, regions, min_score=self.camera_settings.minscore, filter_type=self.camera_settings.filter_type) self.region_count += len(regions) # possibly send a preview image self.send_preview(img_scan) if self.camera_settings.roll_stabilised: roll = 0 else: roll = None pos = self.get_plane_position(frame_time, roll=roll) if pos is not None: self.posmapping[str(frame_time)] = pos # this adds the latlon field to the regions (georeferencing) for r in regions: r.latlon = cuav_util.gps_position_from_image_region( r, pos, w, h, altitude=None, C=self.c_params) if self.joelog: self.log_joe_position(pos, frame_time, regions) # filter out any regions outside the target radius if self.camera_settings.target_radius > 0 and pos is not None: regions = cuav_region.filter_radius( regions, (self.camera_settings.target_latitude, self.camera_settings.target_longitude), self.camera_settings.target_radius) # filter out any regions outside the boundary if self.boundary_polygon: regions = cuav_region.filter_boundary(regions, self.boundary_polygon, pos) #filter by minscore regions = cuav_region.filter_regions( img_scan, regions, min_score=self.camera_settings.minscore, filter_type=self.camera_settings.filter_type) high_score = 1 for r in regions: if r.score > high_score: high_score = r.score if len(regions) > 0 and pos is not None: for r in regions: self.lz.checkaddregion(r, pos) try: lzresult = self.lz.calclandingzone() except Exception as ex: print("calclandingzone failed: ", ex) continue if lzresult: self.transmit_queue.put((lzresult, 100000, None)) if self.msend: self.transmit_queue.put((lzresult, 100000, 'msend')) if len(regions) > 0 and self.camera_settings.transmit: # send a region message with thumbnails to the ground station thumb_img = cuav_region.CompositeThumbnail( img_scan, regions, thumb_size=self.camera_settings.thumbsize) encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), 90] (result, thumb) = cv2.imencode('.jpg', thumb_img, encode_param) pkt = cuav_command.ThumbPacket(frame_time, regions, thumb, pos) if self.transmit_queue.qsize() < 100: self.transmit_queue.put((pkt, None, None)) if self.msend is not None and high_score >= self.camera_settings.m_minscore: self.transmit_queue.put((pkt, None, 'msend')) else: self.send_message("Warning: image Tx queue too long") print("Warning: image Tx queue too long")
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', 'jpeg', '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') if args.vehicle_type == "Copter": icon = slipmap.icon('redcopter.png') else: 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: 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) 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('pitch_stabilised', bool, args.pitch_stabilised, 'Pitch Stabilised'), MPSetting('roll_offset', float, args.roll_offset, 'Roll Offset'), MPSetting('pitch_offset', float, args.pitch_offset, 'Pitch Offset'), 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, False, 'rotate180'), MPSetting('filter_type', str, 'simple', 'Filter Type', choice=['simple']), 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('RegionHue', int, ags.targethue, 'Target Hue (0 to disable)', range=(0,180), increment=1, tab='Imaging'), MPSetting('map_thumbsize', int, args.map_thumbsize, 'Map 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.15, range=(0,100), increment=0.05, digits=2, tab='Image Processing'), MPSetting('MaxRegionArea', float, 1.0, range=(0,100), increment=0.1, digits=1), MPSetting('MinRegionSize', float, 0.2, range=(0,100), increment=0.05, digits=2), MPSetting('MaxRegionSize', float, 1.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('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, map_thumb_size=args.map_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 if camera_settings.pitch_stabilised: pitch = 0 else: pitch = None try: pos = mpos.position(frame_time, roll=roll, pitch=pitch, roll_offset=camera_settings.roll_offset, pitch_offset=camera_settings.pitch_offset) 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 vehicle 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) im_orig = cv2.imread(f) if im_orig is None: continue (w,h) = cuav_util.image_shape(im_orig) if args.downsample: im_full = cv2.resize(im_orig, (0,0), fx=0.5, fy=0.5) else: im_full = im_orig 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']) 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 regions = cuav_region.filter_regions(im_full, regions, min_score=camera_settings.minscore, filter_type=camera_settings.filter_type, target_hue=camera_settings.RegionHue) 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) scan_count += 1 if pos and len(regions) > 0: joelog.add_regions(frame_time, regions, pos, f) mosaic.add_image(pos.time, f, pos) region_count += len(regions) if len(regions) > 0: composite = cuav_region.CompositeThumbnail(im_full, regions) thumbs = cuav_mosaic.ExtractThumbs(composite, len(regions)) thumbsRGB = [] #colour space conversion for thumb in thumbs: thumbsRGB.append(cv2.cvtColor(thumb, cv2.COLOR_BGR2RGB)) mosaic.add_regions(regions, thumbsRGB, f, pos) if args.view: img_view = img_scan (wview,hview) = cuav_util.image_shape(img_view) for r in regions: r.draw_rectangle(img_view, (255,0,0)) #cv.CvtColor(mat, mat, cv.CV_BGR2RGB) img_view = cv2.cvtColor(img_view, cv2.COLOR_BGR2RGB) viewer.set_image(img_view) 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)) #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)