plane_analysis.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 '''
00003 plane_analysis.py
00004 Mac Mason <mac@cs.duke.edu>
00005 
00006 Perform correctness analysis on planes. This assumes that a DB is running.
00007 '''
00008 import sys
00009 import roslib; roslib.load_manifest('semanticmodel')
00010 import rospy
00011 import hand_planes  # Where we get our ground truth from.
00012 from semanticmodel.srv import GetCollectionNamespace
00013 from semanticmodel.msg import Planes
00014 from semanticmodel import point_cloud
00015 import mongo_ros as mr
00016 import shapely.geometry as geo
00017 
00018 if len(sys.argv) < 2:
00019   print "Usage: plane_analysis <bag index> [pct = 0.75] [run_id]"
00020   sys.exit(1)
00021 
00022 index = int(sys.argv[1])
00023 pct = 0.75
00024 min_area = 0.25 
00025 if len(sys.argv) >= 3:
00026   pct = float(sys.argv[2])
00027 
00028 run_id = None
00029 if len(sys.argv) >= 4:
00030   run_id = int(sys.argv[3])
00031 
00032 rospy.init_node('plane_analysis')
00033 
00034 # Figure out what our database is called.
00035 if run_id is not None:
00036   db_name = 'semantic_world_model'
00037   coll_namespace = 'run{0}'.format(run_id)
00038 else:
00039   print "Waiting for get_collection_namespace service..."
00040   rospy.wait_for_service('get_collection_namespace')
00041   gcn_proxy = rospy.ServiceProxy('get_collection_namespace',
00042                                  GetCollectionNamespace)
00043   # And call.
00044   gcn = gcn_proxy()
00045   db_name = gcn.db_name
00046   coll_namespace = gcn.collection_namespace
00047   
00048 planes_mc = mr.MessageCollection(db_name, coll_namespace+'_planes', Planes)
00049 
00050 print "Using db {0} and collection {1}".\
00051       format(db_name, coll_namespace+"_planes")
00052 planes = list(planes_mc.query({}))
00053 print "Found {0} planes".format(len(planes))
00054 
00055 # The data in hand_planes.meters are already in (x, y, z) meters coordinates,
00056 # but the data in planes[0][0].planes[i].hulls are in PointCloud2 format. 
00057 
00058 autos = []
00059 for orig_hull in (x.hull for x in planes[0][0].planes):
00060   autos.append(geo.Polygon(list(point_cloud.read_points(orig_hull, 'xyz'))))
00061 
00062 autos = [x for x in autos if x.area >= min_area]
00063 
00064 hands = []
00065 names = []
00066 for k in hand_planes.meters[index]:
00067   hands.append(geo.Polygon(hand_planes.meters[index][k]))
00068   names.append(k)
00069 
00070 #for (hand, name) in zip(hands, names):
00071 #  print "%s has area %f" % (name, hand.area)
00072 
00073 pairs = [(x, y) for (x, y) in zip(hands, names) if x.area >= min_area]
00074 hands = [x[0] for x in pairs]
00075 names = [x[1] for x in pairs]
00076 
00077 print "After area culling:", len(autos), "autos and", len(hands), "hands."
00078 
00079 # See Section 7 of the paper for definitions.
00080 def approx_subset(a, b):
00081   '''
00082   Is a an approximate subset of b, according to section 7 of the paper?
00083   '''
00084   ai = a.intersection(b).area
00085   return ai >= pct * a.area
00086 
00087 def approx_superset(a, b):
00088   '''
00089   I am an approximate superset of you if you're an approximate subset of me.
00090   '''
00091   return approx_subset(b, a)
00092 
00093 def approx_equals(a, b):
00094   return approx_subset(a, b) and approx_superset(a, b)
00095 
00096 def intersects(a, b):
00097   '''Does a intersect b at all?'''
00098   return a.intersection(b).area > 0.0
00099 
00100 def categorize(autos, hands, index):
00101   '''
00102   Given the set of autos, and hands, and an index (into autos), return the
00103   appropriate categorization of that index. This always returns a tuple whose
00104   first element is in range(1, 6), describing the category; the next value is
00105   the thing it matched against (but see the last return).
00106   '''
00107   for i, hand in enumerate(hands):
00108     if approx_equals(autos[index], hand):
00109       return (1, i)  # autos[index] matched hands[i].
00110   # Not approximately equal to anything.
00111   for i, hand in enumerate(hands):
00112     if approx_subset(autos[index], hand):
00113       return (2, i, index)
00114   # Not equal or an approx_subset.
00115   for i, hand in enumerate(hands):
00116     if approx_superset(autos[index], hand):
00117       return (3, i, index)
00118   # Not equal, sub, or super.
00119   for i, hand in enumerate(hands):
00120     if intersects(autos[index], hand):
00121       return (4, i, index)
00122   # No intersection at all!
00123   return (5, index)  # Second value just makes printing easier
00124 
00125 def false_negatives(autos, hands):
00126   '''
00127   Find the hands that have no autos intersecting them at all.
00128   '''
00129   res = []
00130   for i, hand in enumerate(hands):
00131     hit = False
00132     for auto in autos:
00133       if hand.intersection(auto).area > 0.0:
00134         hit = True
00135     if not hit:
00136       res.append(i)
00137   return res
00138 
00139 categorized = [categorize(autos, hands, i) for i in range(len(autos))]
00140 
00141 truepos = [x for x in categorized if x[0] == 1]
00142 print len(truepos), "True positives:"
00143 for i, tp in enumerate(truepos):
00144   print "    %02d: %s" % (i+1, names[tp[1]])
00145 
00146 print ""
00147 oversegs = [x for x in categorized if x[0] == 2]
00148 print len(oversegs), "Oversegmentations: (intersection / auto, / hand)"
00149 for i, os in enumerate(oversegs):
00150   aa = autos[os[2]].area
00151   ah = hands[os[1]].area
00152   ai = autos[os[2]].intersection(hands[os[1]]).area
00153   print "    %02d: %s: %f %f" % (i+1, names[os[1]], ai / aa, ai / ah)
00154 
00155 print ""
00156 undersegs = [x for x in categorized if x[0] == 3]
00157 print len(undersegs), "Undersegmentations: (intersection / auto, / hand)"
00158 for i, us in enumerate(undersegs):
00159   aa = autos[us[2]].area
00160   ah = hands[us[1]].area
00161   ai = autos[us[2]].intersection(hands[us[1]]).area
00162   print "    %02d: %s: %f %f" % (i+1, names[us[1]], ai / aa, ai / ah)
00163 
00164 print ""
00165 intersections = [x for x in categorized if x[0] == 4]
00166 print len(intersections), "Intersections: (intersection / auto, / hand)"
00167 for i, inter in enumerate(intersections):
00168   aa = autos[inter[2]].area
00169   ah = hands[inter[1]].area
00170   ai = autos[inter[2]].intersection(hands[inter[1]]).area
00171   print "    %02d: %s: %f %f" % (i+1, names[inter[1]], ai / aa, ai / ah)
00172 
00173 print ""
00174 fps = [x for x in categorized if x[0] == 5]
00175 print len(fps), "False positives: (area)"
00176 for i, fp in enumerate(fps):
00177   print "    %02d: %f" % (i+1, autos[fp[1]].area)
00178 
00179 print ""
00180 fns = false_negatives(autos, hands)
00181 print len(fns), "False negatives:"
00182 for i, fn in enumerate(fns):
00183   print "    %02d: %s: %f" % (i+1, names[fn], hands[fn].area)
00184 
00185 # Now, let's figure out (a) our total areas and (b) the total area covered. 
00186 handtotal = sum([x.area for x in hands])
00187 autototal = sum([x.area for x in autos])
00188 print ""
00189 print "Total hand area: %f Total auto area: %f" % (handtotal, autototal)
00190 it = 0.0
00191 for hand in hands:
00192   for auto in autos:
00193     it += hand.intersection(auto).area
00194 print "Intersection total: %f (%f%% of gt)" % (it, 100.0 * it / handtotal)
00195 
00196 # Now, how much area did we find that isn't part of gt?
00197 mistake = 0.0
00198 for i, auto in enumerate(autos):
00199   a = auto.area
00200   for j, hand in enumerate(hands):
00201     a -= auto.intersection(hand).area
00202   mistake += max([a, 0.0])
00203 
00204 print "Error area:", mistake, "percent of total:", 100.0 * mistake / autototal


semanticmodel
Author(s): Julian ("Mac") Mason
autogenerated on Thu Dec 12 2013 12:39:10