00001 
00002 
00003 import os
00004 import numpy as np
00005 import pickle as pk
00006 import time
00007 
00008 
00009 
00010 
00011 
00012 from opencv.cv import *
00013 from opencv.highgui import *
00014 import numpy as np
00015 import Image as Image
00016 
00017 
00018 
00019 
00020 def getTime():
00021     return '['+time.strftime("%H:%M:%S", time.localtime())+']'
00022 
00023 def standard_rad(t):
00024     if t > 0:
00025         return ((t + np.pi) % (np.pi * 2))  - np.pi
00026     else:
00027         return ((t - np.pi) % (np.pi * -2)) + np.pi
00028 
00029 
00030 
00031 
00032 
00033 
00034 def list_mat_to_mat(list_mat, axis=0):
00035     return np.concatenate(tuple(list_mat), axis=axis)
00036 
00037 
00038 
00039 
00040 def formatted_time():
00041     date_name = time.strftime('%Y%h%d_%H%M%S', time.localtime())
00042 
00043 
00044     return date_name
00045 
00046 
00047 
00048 
00049 def load_pickle(filename):
00050     p = open(filename, 'r')
00051     picklelicious = pk.load(p)
00052     p.close()
00053     return picklelicious
00054 
00055 
00056 
00057 
00058 def save_pickle(object, filename):
00059     pickle_file = open(filename, 'w')
00060     pk.dump(object, pickle_file)
00061     pickle_file.close()
00062 
00063 
00064 
00065 def norm(mat):
00066     return np.power(np.sum(np.power(mat,2), axis=0), 0.5)
00067 
00068 
00069 def approx_equal(a, b, epsilon=.001):
00070     return (b < (a+epsilon)) and ((a-epsilon) < b)
00071 
00072 
00073 def unipolar_limit( x, upper ):
00074     """ limit the value of x such that
00075         0 <= x <= upper
00076     """
00077 
00078     if x > upper:
00079         x=upper
00080     if x < 0:
00081         x=0
00082 
00083     return x
00084 
00085 def cart_of_pol(p):
00086    """ Finds cartesian coordinates of polar points [r, t]' """
00087    r = p[0,:]
00088    t = p[1,:]
00089    x = numpy.multiply(numpy.cos(t), r)
00090    y = numpy.multiply(numpy.sin(t), r)
00091    return numpy.vstack((x,y))
00092 
00093 def pol_of_cart(p):
00094     """ Find polar coordinates of cartesian points [x, y]' """
00095     norm = numpy.linalg.norm(p)
00096     ang = math.atan2(p[1,0], p[0,0])
00097     return numpy.matrix([norm, ang]).T
00098 
00099 
00100 
00101 
00102 def bound(value, lower, upper):
00103     if lower >= upper:
00104         t = lower
00105         lower = upper
00106         upper = t
00107 
00108     
00109     ret_val = min(max(value, lower), upper)
00110 
00111 
00112     return ret_val
00113 
00114 
00115 
00116 
00117 
00118 
00119 
00120 def wrap_np_array(nparr):
00121     shp = nparr.shape
00122     npstr = nparr.tostring()
00123     npdtype = str(nparr.dtype)
00124     nparr_ros = NumpyArray(None,npstr,shp,npdtype)
00125     return nparr_ros
00126 
00127 
00128 
00129 
00130 def unwrap_np_array(nparr_ros):
00131     npstr,shp,npdtype = nparr_ros.data,nparr_ros.shape,nparr_ros.dtype
00132     nparr = np.fromstring(npstr,dtype=npdtype)
00133     nparr = nparr.reshape(shp)
00134     return nparr
00135 
00136 
00137 
00138 
00139 
00140 
00141 
00142 
00143 def cartesian_product(lists, previous_elements = []):
00144     if len(lists) == 1:
00145         for elem in lists[0]:
00146             yield previous_elements + [elem, ]
00147     else:
00148         for elem in lists[0]:
00149             for x in cartesian_product(lists[1:], previous_elements + [elem, ]):
00150                 yield x
00151 
00152 
00153 
00154 
00155 def choose_without_replacement(list, n):
00156     lists = [list for i in range(n)]
00157     return _choose_without_replacement(lists)
00158 
00159 def _choose_without_replacement(lists,previous_elements=[],ignore_count=0):
00160     if len(lists) == 1:
00161         for elem in lists[0][ignore_count:]:
00162             yield previous_elements + [elem, ]
00163     else:
00164         for i,elem in enumerate(lists[0][ignore_count:]):
00165             for x in _choose_without_replacement(lists[1:],previous_elements + [elem, ],ignore_count+i+1):
00166                 yield x
00167 
00168 
00169 
00170 
00171 def say(text):
00172     os.system( 'echo "' + text + '" | festival --tts' )
00173 
00174 
00175 
00176 
00177 
00178 def matrixrank(A,tol=1e-8):
00179     s = np.linalg.svd(A,compute_uv=0)
00180     return sum( np.where( s>tol, 1, 0 ) )
00181 
00182 
00183 
00184 
00185 
00186 
00187 
00188 
00189 
00190 
00191 
00192 
00193 cv2np_type_dict = {CV_16S      : (np.int16, 1),  
00194                    CV_16SC1  : (np.int16, 1),   
00195                    CV_16SC2  : (np.int16, 2),   
00196                    CV_16SC3  : (np.int16, 3),   
00197                    CV_16SC4  : (np.int16, 4),   
00198                    CV_16U      : (np.uint16, 1),   
00199                    CV_16UC1  : (np.uint16, 1),   
00200                    CV_16UC2  : (np.uint16, 2),   
00201                    CV_16UC3  : (np.uint16, 3),   
00202                    CV_16UC4  : (np.uint16, 4),   
00203                    CV_32F      : (np.float32, 1),   
00204                    CV_32FC1  : (np.float32, 1),   
00205                    CV_32FC2  : (np.float32, 2),   
00206                    CV_32FC3  : (np.float32, 3),   
00207                    CV_32FC4  : (np.float32, 4),   
00208                    CV_32S      : (np.int32, 1),   
00209                    CV_32SC1  : (np.int32, 1),   
00210                    CV_32SC2  : (np.int32, 2),   
00211                    CV_32SC3  : (np.int32, 3),   
00212                    CV_32SC4  : (np.int32, 4),   
00213                    CV_64F      : (np.float64, 1),   
00214                    CV_64FC1  : (np.float64, 1),   
00215                    CV_64FC2  : (np.float64, 2),   
00216                    CV_64FC3  : (np.float64, 3),   
00217                    CV_64FC4  : (np.float64, 4),   
00218                    CV_8S    : (np.int8, 1),   
00219                    CV_8SC1    : (np.int8, 1),   
00220                    CV_8SC2    : (np.int8, 2),   
00221                    CV_8SC3    : (np.int8, 3),   
00222                    CV_8SC4    : (np.int8, 4),   
00223                    CV_8U    : (np.uint8, 1),   
00224                    CV_8UC1    : (np.uint8, 1),   
00225                    CV_8UC2    : (np.uint8, 2),   
00226                    CV_8UC3    : (np.uint8, 3),   
00227                    CV_8UC4    : (np.uint8, 4)}
00228 
00229 
00230 cv2np_type_dict_invertible = {CV_16SC1   : (np.int16, 1),   
00231                               CV_16SC2   : (np.int16, 2),   
00232                               CV_16SC3   : (np.int16, 3),   
00233                               CV_16SC4   : (np.int16, 4),   
00234                               CV_16UC1   : (np.uint16, 1),   
00235                               CV_16UC2   : (np.uint16, 2),   
00236                               CV_16UC3   : (np.uint16, 3),   
00237                               CV_16UC4   : (np.uint16, 4),   
00238                               CV_32FC1   : (np.float32, 1),   
00239                               CV_32FC2   : (np.float32, 2),   
00240                               CV_32FC3   : (np.float32, 3),   
00241                               CV_32FC4   : (np.float32, 4),   
00242                               CV_32SC1   : (np.int32, 1),   
00243                               CV_32SC2   : (np.int32, 2),   
00244                               CV_32SC3   : (np.int32, 3),   
00245                               CV_32SC4   : (np.int32, 4),   
00246                               CV_64FC1   : (np.float64, 1),   
00247                               CV_64FC2   : (np.float64, 2),   
00248                               CV_64FC3   : (np.float64, 3),   
00249                               CV_64FC4   : (np.float64, 4),   
00250                               CV_8SC1     : (np.int8, 1),   
00251                               CV_8SC2     : (np.int8, 2),   
00252                               CV_8SC3     : (np.int8, 3),   
00253                               CV_8SC4     : (np.int8, 4),   
00254                               CV_8UC1     : (np.uint8, 1),   
00255                               CV_8UC2     : (np.uint8, 2),   
00256                               CV_8UC3     : (np.uint8, 3),   
00257                               CV_8UC4     : (np.uint8, 4)}
00258 
00259 
00260 
00261 
00262 
00263 
00264 
00265 
00266 def cv2np(im, format='RGB'):
00267     """This function converts an image from openCV format to a numpy array.
00268        This utility needs both NUMPY and OPENCV to accomplish the conversion.
00269        cv2np(im, format='RGB')
00270     """
00271     if format == 'BGR':
00272         cvCvtColor( im, im, CV_BGR2RGB )
00273     numpy_type, nchannels = cv2np_type_dict[cvGetElemType(im)]
00274     array_size = [im.height, im.width, nchannels]
00275     
00276     
00277 
00278     if im.__doc__ == None:
00279         
00280         return im.as_numpy_array()
00281     else:
00282         np_im = np.array( np.frombuffer(im.imageData, dtype=numpy_type, 
00283                             count=im.height*im.width*nchannels))
00284 
00285     return np.reshape(np_im, array_size)
00286     
00287     
00288     
00289 def np2pil( im ):
00290     """ for grayscale - all values must be between 0 and 255.
00291             not sure about color yet.
00292         np2pil(im)
00293     """
00294     
00295     
00296     if len(im.shape) == 3:
00297         shp = im.shape
00298         channels = shp[2]
00299         height, width = shp[0], shp[1]
00300     elif len(im.shape) == 2:
00301         height, width = im.shape
00302         channels = 1
00303     else:
00304         raise AssertionError("unrecognized shape for the input image. should be 3 or 2, but was %d." % len(im.shape))
00305 
00306     if channels == 3:
00307         image = Image.fromstring( "RGB", (width, height), im.tostring() )
00308     if channels == 1:
00309         im = np.array(im, dtype=np.uint8)
00310         
00311         image = Image.fromstring( "L", (width, height), im.tostring() )
00312 
00313     return image
00314 
00315 
00316 if True:
00317     np2cv_type_dict = dict([(str(np.dtype(v[0])), v[1]), k] for
00318                            k,v in cv2np_type_dict_invertible.items())
00319 
00320 
00321     def np2cv(im, force_color=False):
00322         ''' Note: force_color -- force grayscale np image into a color cv image
00323             np2cv(im, force_color=False)
00324         '''
00325         image = np2pil( im )
00326         image.save('test.bmp', 'BMP')
00327         if len(im.shape) == 3:
00328             cvim = cvLoadImage('test.bmp')
00329         elif len(im.shape) == 2:
00330             if force_color == False:
00331                 cvim = cvLoadImage('test.bmp', CV_LOAD_IMAGE_GRAYSCALE)
00332             else:
00333                 cvim = cvLoadImage('test.bmp')
00334         else:
00335             raise AssertionError("unrecognized shape for the input image. should be 3 or 2, but was %d." % len(im.shape))
00336 
00337         return cvim
00338