$search
00001 # Software License Agreement (BSD License) 00002 # 00003 # Copyright (c) 2008, Willow Garage, Inc. 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions 00008 # are met: 00009 # 00010 # * Redistributions of source code must retain the above copyright 00011 # notice, this list of conditions and the following disclaimer. 00012 # * Redistributions in binary form must reproduce the above 00013 # copyright notice, this list of conditions and the following 00014 # disclaimer in the documentation and/or other materials provided 00015 # with the distribution. 00016 # * Neither the name of Willow Garage, Inc. nor the names of its 00017 # contributors may be used to endorse or promote products derived 00018 # from this software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 # POSSIBILITY OF SUCH DAMAGE. 00032 # 00033 # Author: Bhaskara Marthi 00034 00035 # Code for data association and registration of planes across frames 00036 00037 import scipy as sp 00038 import numpy as np 00039 import numpy.linalg as lin 00040 import semanticmodel.msg as sm 00041 import geometry_msgs.msg as gm 00042 import visualization_msgs.msg as vm 00043 from rospy import loginfo, logdebug 00044 import copy 00045 from std_msgs.msg import ColorRGBA 00046 from random import random 00047 import convexhull as ch 00048 import logging 00049 00050 LOG=logging.getLogger('world_model.planes') 00051 00052 DEFAULT_MAX_DISP=0.2 00053 COLORS = [] 00054 00055 class BoundedPlane: 00056 "Represents a polygonal subset of a plane in 3-space" 00057 00058 def __init__(self, p): 00059 "Init from a Plane message" 00060 00061 self.header = p.header 00062 00063 workaround_incorrect_planes(p) 00064 00065 # Normalize the plane equation 00066 self.n, self.d = normalize_eq(p) 00067 00068 # Figure out transforms between plane and world coordinates 00069 assert(len(p.polygon)>2) 00070 p0 = p.polygon[0] 00071 p1 = p.polygon[1] 00072 p0 = np.array([p0.x, p0.y, p0.z]) 00073 p1 = np.array([p1.x, p1.y, p1.z]) 00074 v1 = normalize(p1-p0) # First basis vector is along polygon side 00075 v2 = normalize(np.cross(self.n, v1)) # Orthogonal basis vector in plane 00076 h1 = np.hstack([v1,0]) 00077 h2 = np.hstack([v2,0]) 00078 h3 = np.hstack([self.n,0]) 00079 h4 = np.hstack([p0,1]) 00080 00081 00082 # Store transform from plane coords to world as homogeneous matrix 00083 self.p2w = np.vstack([h1,h2,h3,h4]).T 00084 00085 # Store transform from world to plane 00086 self.w2p = lin.inv(self.p2w) 00087 00088 # Transform bounding polygon into planar coordinates 00089 self.polygon = [mult(self.w2p, p)[0:2] for p in p.polygon] 00090 00091 00092 def __repr__(self): 00093 return "n=[{0}, {1}, {2}], d={3}".\ 00094 format(self.n[0], self.n[1], self.n[2], self.d)# [to_tuple(p) for p in self.polygon]) 00095 00096 00097 def intersect(p1, p2, max_disp=DEFAULT_MAX_DISP): 00098 """ 00099 Checks if: 00100 1) the two sets lie on the same plane (approximately) 00101 2) the polygons intersect 00102 """ 00103 #loginfo("Checking if {0} and {1} intersect".format(p1, p2)) 00104 trans = np.dot(p1.w2p, p2.p2w) 00105 poly2 = [trans2d(trans, p)[0:3] for p in p2.polygon] 00106 00107 # Check that all the points approximately lie on the plane 00108 for i in range(len(poly2)): 00109 if abs(poly2[i][2])>max_disp: 00110 return False 00111 else: 00112 poly2 = [p[0:2] for p in poly2] 00113 res = polygons_intersect(p1.polygon, poly2) 00114 return res 00115 00116 def merge_planes(planes, p, max_disp=DEFAULT_MAX_DISP): 00117 """ 00118 P must intersect at least one plane. Combine it with that plane, then 00119 process any additional intersections that result. 00120 """ 00121 planes = planes.copy() 00122 int_planes = [id for id, existing in planes.items() 00123 if intersect(p, existing, max_disp)] 00124 assert int_planes 00125 i = int_planes[0] 00126 LOG.debug("Merging new plane with {0}".format(i)) 00127 planes[i] = combine(planes[i], p) 00128 00129 merged = True 00130 while merged: 00131 merged = False 00132 LOG.debug("Checking for additional intersections") 00133 for j, pl in planes.items(): 00134 LOG.debug("Checking {0}".format(j)) 00135 if j != i: 00136 if intersect(planes[i], planes[j], max_disp): 00137 planes[i] = combine(planes[i], planes[j]) 00138 del planes[j] 00139 merged = True 00140 LOG.debug("Merged with {0}".format(j)) 00141 break 00142 return planes 00143 00144 00145 def combine(p1, p2): 00146 """ 00147 Combines the two bounded planes to form a new one 00148 """ 00149 combined = copy.deepcopy(p1) 00150 poly = [to_tuple(p) for p in p1.polygon] 00151 trans = np.dot(p1.w2p, p2.p2w) 00152 for p in p2.polygon: 00153 poly.append(to_tuple(trans2d(trans, p))) 00154 hull = ch.convex_hull(poly) 00155 combined.polygon = map(np.array, hull) 00156 #logdebug("Combined {0} and {1}. New poly is {2}".\ 00157 # format([to_tuple(p) for p in p1.polygon], 00158 # [to_tuple(p) for p in p2.polygon], 00159 # list(hull))) 00160 return combined 00161 00162 def to_plane_msg(bp): 00163 "Turn a BoundedPlane object into a Plane message" 00164 p = sm.Plane() 00165 p.header = bp.header 00166 p.a, p.b, p.c = bp.n 00167 p.d = bp.d 00168 p.polygon = [trans_to_pt(bp.p2w, pt) for pt in bp.polygon] 00169 sx = sum((pt.x for pt in p.polygon)) 00170 sy = sum((pt.y for pt in p.polygon)) 00171 sz = sum((pt.z for pt in p.polygon)) 00172 np = len(p.polygon) 00173 p.center.x = sx/np 00174 p.center.y = sy/np 00175 p.center.z = sz/np 00176 return p 00177 00178 def to_marker(planes, timestamp=None): 00179 "Convert list of bounded planes to visualization markers" 00180 assert(len(planes)>0) 00181 marker = vm.Marker() 00182 marker.header.frame_id = planes[0].header.frame_id 00183 if timestamp: 00184 marker.header.stamp = timestamp 00185 marker.ns = 'planes' 00186 marker.type = vm.Marker.LINE_LIST 00187 marker.action = vm.Marker.ADD 00188 marker.scale.x = 0.01 00189 marker.color.a = 1.0 00190 marker.color.b = 1.0 00191 marker.color.r = 0.75 00192 00193 while len(COLORS)<=len(planes): 00194 COLORS.append(ColorRGBA(a=1.0, r=random(), g=random(), b=random())) 00195 00196 for color,bp in zip(COLORS, planes): 00197 n = len(bp.polygon) 00198 for i in range(n): 00199 j = i-1 if i>0 else n-1 00200 marker.points.append(trans_to_pt(bp.p2w, bp.polygon[j])) 00201 marker.points.append(trans_to_pt(bp.p2w, bp.polygon[i])) 00202 marker.colors.append(color) 00203 marker.colors.append(color) 00204 00205 return marker 00206 00207 00208 ############################################################ 00209 # Internal 00210 ############################################################ 00211 00212 def to_tuple(p): 00213 "Needed to convert between numpy and opencv" 00214 return (p[0], p[1]) 00215 00216 def workaround_incorrect_planes(m): 00217 n = len(m.polygon) 00218 new_d = 0 00219 for pt in m.polygon: 00220 inc = (m.a*pt.x + m.b*pt.y + m.c*pt.z) 00221 new_d += inc/n 00222 m.d = new_d 00223 00224 00225 00226 def mult(m, p): 00227 "Multiply numpy homogeneous matrix * geometry_msgs.Point" 00228 return np.dot(m, [p.x, p.y, p.z, 1]) 00229 00230 def trans2d(m, p): 00231 "Transform 2d pt using homogeneous matrix" 00232 return np.dot(m, np.hstack([p, 0, 1]))[0:3] 00233 00234 def trans_to_pt(m, p): 00235 "Transform 2d pt using m and convert to geometry_msgs.Point" 00236 return gm.Point(*trans2d(m, p)) 00237 00238 def normalize_eq(m): 00239 v = np.array([m.a, m.b, m.c]) 00240 return normalize(v), m.d/lin.norm(v) 00241 00242 def normalize(v): 00243 return v/lin.norm(v) 00244 00245 def polygons_intersect(p1, p2): 00246 return one_sided_intersect(p1, p2) or one_sided_intersect(p2, p1) 00247 00248 def one_sided_intersect(p1, p2): 00249 """ 00250 Iterate over sides of P1 and see if one of them separates the two polygons. 00251 If there is, the polygons don't intersect. 00252 """ 00253 n = len(p1) 00254 for i in range(n): 00255 j = i-1 if i>0 else n-1 00256 min1, max1 = project_onto_normal(p1, p1[i], p1[j]) 00257 min2, max2 = project_onto_normal(p2, p1[i], p1[j]) 00258 if max2<min1 or max1<min2: 00259 return False 00260 return True 00261 00262 def project_onto_normal(poly, q1, q2): 00263 "Project points of poly onto normal to line between q1 and q2" 00264 d = q2-q1 00265 perp = normalize(np.array((d[1], -d[0]))) 00266 inf = None 00267 sup = None 00268 for p in poly: 00269 proj = np.dot(perp, p) 00270 if inf is None or proj<inf: 00271 inf = proj 00272 if sup is None or proj>sup: 00273 sup = proj 00274 assert inf is not None 00275 assert sup is not None 00276 return (inf, sup) 00277 00278 00279 00280 ############################################################ 00281 # Examples 00282 ############################################################ 00283 00284 # These defs don't work any more 00285 # 00286 # 2 intersects 3 and 4 00287 # 3 and 4 don't intersect 00288 # 00289 # m = [] 00290 # m.append(sm.Plane()) 00291 # m[0].a = 1 00292 # m[0].b = 0 00293 # m[0].c = -1 00294 # m[0].d = 4 00295 # m[0].hull.append(gm.Point(1,2,-3)) 00296 # m[0].hull.append(gm.Point(6,4,2)) 00297 # m[0].hull.append(gm.Point(3,-1,4)) 00298 00299 # m.append(sm.Plane()) 00300 # m[1].c = 1 00301 # m[1].d = 3 00302 # m[1].hull.append(gm.Point(1,2,3)) 00303 # m[1].hull.append(gm.Point(4,5,3)) 00304 # m[1].hull.append(gm.Point(4,0,3)) 00305 00306 # m.append(sm.Plane()) 00307 # m[2].c = 2 00308 # m[2].d = 6 00309 # m[2].hull.append(gm.Point(3,2,3)) 00310 # m[2].hull.append(gm.Point(3,8,3)) 00311 # m[2].hull.append(gm.Point(6,8,3)) 00312 # m[2].hull.append(gm.Point(6,2,3)) 00313 00314 # m.append(sm.Plane()) 00315 # m[3].c = 1 00316 # m[3].d = 3 00317 # m[3].hull.append(gm.Point(2,2,3)) 00318 # m[3].hull.append(gm.Point(2,6,3)) 00319 # m[3].hull.append(gm.Point(-1,6,3)) 00320 # m[3].hull.append(gm.Point(-1,2,3)) 00321 00322 00323 # for msg in m: 00324 # msg.header.frame_id = '/map'