gaussian_curvature.py
Go to the documentation of this file.
00001 #
00002 # Copyright (c) 2010, Georgia Tech Research Corporation
00003 # All rights reserved.
00004 #
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions are met:
00007 #     * Redistributions of source code must retain the above copyright
00008 #       notice, this list of conditions and the following disclaimer.
00009 #     * Redistributions in binary form must reproduce the above copyright
00010 #       notice, this list of conditions and the following disclaimer in the
00011 #       documentation and/or other materials provided with the distribution.
00012 #     * Neither the name of the Georgia Tech Research Corporation nor the
00013 #       names of its contributors may be used to endorse or promote products
00014 #       derived from this software without specific prior written permission.
00015 #
00016 # THIS SOFTWARE IS PROVIDED BY GEORGIA TECH RESEARCH CORPORATION ''AS IS'' AND
00017 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 # DISCLAIMED. IN NO EVENT SHALL GEORGIA TECH BE LIABLE FOR ANY DIRECT, INDIRECT,
00020 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00021 # LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00022 # OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00023 # LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00024 # OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00025 # ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 #
00027 
00028 #  \author Hai Nguyen (Healthcare Robotics Lab, Georgia Tech.)
00029 import numpy as np
00030 ### Optional imports below:
00031 #       from enthought.mayavi import mlab [3d plotting]
00032 
00033     
00034 ##
00035 # Fits a plane
00036 # 
00037 # @param points 3xn numpy matrix representing points to be fitted
00038 # @param d direction that normal calculated should point in
00039 # @return normal and eigen value points (in descending order) 
00040 def gaussian_curvature(points, p=np.matrix([0,0,1]).T):    
00041     assert(points.shape[0] == 3)    
00042     if points.shape[1] < 2:
00043         return np.matrix([0, 0, 0.0]).T, np.array([0, 0, 0.0])
00044     c = np.cov(points)
00045     try:
00046         u, s, vh = np.linalg.svd(c)
00047         u = np.matrix(u)  
00048     
00049         #select the 3rd eigenvector, assoc. with the smallest eigenvalue
00050         if u[:,2].T * p < 0:
00051             return -u[:,2], s
00052         else:
00053             return u[:,2], s
00054     except np.linalg.linalg.LinAlgError, e:
00055         print e
00056         print 'oh no!!!!!! why is this happening?'
00057         print points.shape
00058         print c        
00059         print points
00060     
00061 def spread(points):
00062     assert(points.shape[0] == 3)
00063     if points.shape[1] < 2:
00064         return np.matrix([0, 0, 0.0]).T, np.array([0, 0, 0.0])
00065    
00066     c = np.cov(points)
00067     u, s, vh = np.linalg.svd(c)
00068     u = np.matrix(u)      
00069     return u[:,0:2], s[0:2]
00070     
00071     
00072 ##
00073 # Calculates a coordinate system  & eigen values of given points matrix 
00074 #
00075 # @param points 3xn numpy matrix representing points to be fitted
00076 # @param x first principle direction to match to
00077 # @param z second direction to match to
00078 # @return (3x3 matrix describe coordinate frame, list with associated eigen values) 
00079 def gaussian_curvature2(points, x=np.matrix([1,0,0]).T, z=np.matrix([0,0,1]).T):
00080     assert(points.shape[0] == 3)
00081     #svd
00082     c = np.cov(points)
00083     u, s, vh = np.linalg.svd(c)
00084     u = np.matrix(u)  
00085       
00086     choices = range(3)
00087     #find correspondences
00088     z_distances = [np.degrees(np.arccos(np.abs(z.T * u[:,i])))[0,0] for i in choices]
00089     z_choice = choices[np.argmin(z_distances)]    
00090 #    print z.T, z_distances, z_choice
00091 #    print 'remaining', choices, 'removing', z_choice
00092     choices.remove(z_choice)    
00093     
00094     x_distances = [np.degrees(np.arccos(np.abs(x.T * u[:,i])))[0,0] for i in choices]
00095     x_choice = choices[np.argmin(x_distances)]
00096 #    print x.T, x_distances, x_choice
00097 #    print 'remaining', choices, 'removing', x_choice
00098     choices.remove(x_choice)    
00099     
00100     #reorder
00101     xv = u[:,x_choice]
00102     xs = s[x_choice]
00103     
00104     ys = s[choices[0]]
00105         
00106     zv = u[:,z_choice]
00107     zs = s[z_choice]
00108     
00109     #check directions
00110     if np.degrees(np.arccos(xv.T * x)) > 90.0:
00111         xv = -xv
00112     if np.degrees(np.arccos(zv.T * z)) > 90.0:
00113         zv = -zv
00114     
00115     #find third vector
00116     yv = np.matrix(np.cross(xv.T, zv.T)).T
00117     directions = np.concatenate([xv, yv, zv], axis=1)
00118     sd = [xs, ys, zs]
00119     if np.linalg.det(directions) < 0:
00120         directions[:,1] = -directions[:,1]
00121     assert np.linalg.det(directions) > 0        
00122     return directions, sd
00123 
00124         
00125 def plot_axis(x,y, z, directions):
00126     from enthought.mayavi import mlab
00127     mlab.quiver3d(x, y, z, [directions[0,0]], [directions[1,0]], [directions[2,0]], scale_factor=1, color=(1,0,0))
00128     if directions.shape[1] > 1:
00129         mlab.quiver3d(x, y, z, [directions[0,1]], [directions[1,1]], [directions[2,1]], scale_factor=1, color=(0,1,0))
00130         mlab.quiver3d(x, y, z, [directions[0,2]], [directions[1,2]], [directions[2,2]], scale_factor=1, color=(0,0,1))        
00131     
00132 def generate_pts():    
00133     #Generate random points on a disc
00134     radius = np.random.random((1, 2000))
00135     angle = np.random.random((1,2000)) * 2*np.pi
00136     x = radius * np.cos(angle)
00137     y = radius * np.sin(angle)
00138     r = np.concatenate((x,y))    
00139     r[0,:] = r[0,:] * 2
00140     xy_plane = np.matrix(np.eye(3))[:,(0, 2)]
00141     pts = xy_plane * r
00142     return pts
00143     
00144     
00145 def demo1():
00146     from enthought.mayavi import mlab
00147     pts = generate_pts()
00148     directions, magnitudes = gaussian_curvature(pts)
00149     print directions.T.A[0].tolist()
00150 
00151     print magnitudes.tolist()
00152     mlab.points3d(pts[0,:].A1, pts[1,:].A1, pts[2,:].A1, mode='sphere', scale_factor=.05)
00153     plot_axis(0,0,0, directions)
00154     plot_axis(2,0,0, np.eye(3))
00155     mlab.show()
00156 
00157 def demo2():
00158     from enthought.mayavi import mlab
00159     pts = generate_pts()
00160     direction, magnitudes = gaussian_curvature(pts)    
00161     print 'eigen values', magnitudes.T
00162     mlab.points3d(pts[0,:].A1, pts[1,:].A1, pts[2,:].A1, mode='sphere', scale_factor=.05)
00163     plot_axis(0,0,0, direction)
00164     plot_axis(2,0,0, np.eye(3))
00165     mlab.show()    
00166 
00167 if __name__ == '__main__':
00168     demo1()
00169     
00170     
00171     
00172     
00173     
00174     
00175     
00176     
00177     
00178     
00179     
00180     
00181     
00182     
00183     
00184     
00185     
00186     
00187     
00188     
00189     
00190     
00191     
00192     
00193     
00194     
00195     
00196     
00197     
00198     
00199     
00200     
00201     
00202     
00203 #    #U is unordered, we reorder it according to given x and z
00204 #    u      = np.matrix(u)
00205 #    vecs   = [u[:,i] / np.linalg.norm(u[:,i]) for i in range(3)]
00206 #    s_list = [s[i] for i in range(3)]
00207 #    canon  = [v / np.linalg.norm(v) for v in [x, z]]
00208 #
00209 #    ordered_vecs = []
00210 #    ordered_s = [](x.T * u[
00211 #    for idx, v in enumerate(vecs):    
00212 #        angles = []        
00213 #        for d in canon:
00214 #            sep = np.degrees(np.arccos(d.T * v))[0,0]
00215 #            if sep == 180:
00216 #                sep = 0
00217 #            angles.append(sep)            
00218 #        min_idx = np.argmin(angles)        
00219 #        ordered_vecs.append(vecs.pop(min_idx))
00220 #        ordered_s.append(s_list.pop(min_idx))
00221 #        
00222 #    #pdb.set_trace()
00223     #ordered_vecs.append(np.matrix(np.cross(ordered_vecs[0].T, ordered_vecs[1].T)).T)
00224 #    xe = ordered_vecs[0]
00225 #    ye = ordered_vecs[2]
00226 #    ze = ordered_vecs[1]
00227 #    ordered_vecs = [xe, ye, ze]    
00228 #        
00229 #    ordered_s.append(s_list[0])
00230 #    ordered_s = [ordered_s[0], ordered_s[2], ordered_s[1]]
00231 #    ordered_s = np.matrix(ordered_s).T
00232 #    print ordered_s
00233 #    
00234 #    reordered = np.concatenate(ordered_vecs, axis=1)
00235 #    if np.linalg.det(reordered) < 0:
00236 #        reordered[:,1] = -reordered[:,1]
00237 #        ordered_s[1,0] = -ordered_s[1,0]
00238 #        
00239 #    return reordered, ordered_s     
00240     
00241     
00242     
00243     
00244     
00245     
00246     
00247     
00248     
00249     
00250     
00251     
00252     
00253     
00254     
00255     


clutter_segmentation
Author(s): Jason Okerman, Martin Schuster, Advisors: Prof. Charlie Kemp and Jim Regh, Lab: Healthcare Robotics Lab at Georgia Tech
autogenerated on Wed Nov 27 2013 12:07:15