00001
00002
00003 '''
00004 SeedMea.py
00005 Copyright 2013 University of Massachusetts Lowell
00006 Author: Abraham Shultz, Jonathan Hasenzahl
00007 '''
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042 import roslib; roslib.load_manifest('neuro_recv')
00043 import rospy
00044 import math
00045 import numpy as np
00046 import networkx as nx
00047 import pygame
00048 from pickle import Pickler
00049 import datetime
00050 from brian import *
00051 import random
00052 from pprint import pprint
00053 import Image
00054
00055
00056
00057
00058
00059 class Channel():
00060 def __init__(self):
00061 self.neurons = []
00062 self.total_weight = 0.0
00063
00064 def __str__(self):
00065 name = 'Weight:' + str(self.total_weight)
00066 if len(self.neurons) == 0:
00067 name += '[No neurons]'
00068 else:
00069 for neuron in self.neurons:
00070 name += '[' + str(neuron) + ']'
00071 return name
00072
00073 def add(self, neuron):
00074 self.neurons.append(neuron)
00075 self.total_weight += neuron.weight
00076
00077 def size(self):
00078 return len(self.neurons)
00079
00080
00081
00082
00083 class CloseNeuron():
00084 def __init__(self, data, dist):
00085 self.data = data
00086 self.weight = 40.0 - dist
00087
00088 def __str__(self):
00089 return str(self.data) + ':' + str(self.weight)
00090
00091
00092
00093
00094
00095 def genPCell(density_map):
00096
00097 max_x, max_y = density_map.shape
00098 random.seed()
00099
00100
00101 density_map[0][0] = random.random()
00102 density_map[max_x -1][0] = random.random()
00103 density_map[0][max_y - 1] = random.random()
00104 density_map[max_x-1][max_y-1] = random.random()
00105
00106
00107 squarePlasma(density_map)
00108
00109 def displace(size, originalSize):
00110 max = (float(size)/float(originalSize)) * 3.00
00111 displacement = (random.random() - 0.5) * max
00112 return displacement
00113
00114 def diSqPlasma(array):
00115 pass
00116
00117 def squarePlasma(array):
00118 if array.shape == (2,2):
00119 return
00120
00121
00122 height, width = array.shape
00123 array[height/2][width-1] = (array[0][width-1] + array[height-1][width-1])/2
00124 array[height/2][0] = (array[0][0] + array[height-1][0])/2
00125 array[0][width/2] = (array[0][0] + array[0][width-1])/2
00126 array[height-1][width/2] = (array[height-1][0] + array[height-1][width-1])/2
00127
00128
00129 center = 0
00130 center += array[height/2][width-1]
00131 center += array[height/2][0]
00132 center += array[0][width/2]
00133 center += array[height-1][width/2]
00134 center = center/4
00135
00136 center += displace(height+width, 257*2)
00137 if center > 1:
00138 center = 1
00139 if center < 0:
00140 center = 0;
00141
00142 array[height/2][width/2] = center
00143
00144
00145 squarePlasma(array[0:height/2+1,0:width/2+1])
00146 squarePlasma(array[0:height/2+1,width/2:width])
00147 squarePlasma(array[height/2:height,0:width/2+1])
00148 squarePlasma(array[height/2:height,width/2:width])
00149
00150
00151
00152 def nextPowTwo(start):
00153 y = math.floor(math.log(start,2))
00154 return int(math.pow(2, y+1))
00155
00156
00157
00158
00159 def gaussConnect(distance, center):
00160 return math.e - ((distance - center)**2)/(2*center/2)**2
00161
00162
00163
00164 def renderMap(densityData, title):
00165 if densityData.ndim != 2:
00166 print "Can only render 2-D arrays"
00167
00168
00169
00170 win = pygame.display.set_mode(densityData.shape)
00171 win.fill((0,0,0))
00172 pygame.display.set_caption(title)
00173 screen = pygame.display.get_surface()
00174 color = densityData * 255
00175 color = color.astype(int)
00176 pygame.surfarray.blit_array(screen, color)
00177 pygame.display.flip()
00178
00179
00180 pic = Image.fromarray(color.astype(float))
00181 pic.convert('RGB').save("{0}.png".format(title), "PNG")
00182
00183 while 1:
00184 for event in pygame.event.get():
00185 if event.type == pygame.QUIT:
00186 return
00187
00188 def grimReap(density_map, survival_rate):
00189
00190 x_max, y_max = density_map.shape
00191 for ii in xrange(0,x_max):
00192 for jj in xrange(0, y_max):
00193 if random.random() > survival_rate/100.00:
00194 density_map[ii][jj] = 0
00195
00196 def densityReap(density_map, expected_cells):
00197
00198 total_cells = 0
00199 for cell in density_map.flat:
00200 total_cells += cell
00201
00202 surplus = total_cells - expected_cells
00203 print "total: ", total_cells
00204 print "expected: ", expected_cells
00205 print "surplus: ", surplus
00206 x_max, y_max = density_map.shape
00207
00208
00209 while surplus > 0:
00210
00211 rand_X = random.randint(0,x_max-1)
00212 rand_Y = random.randint(0,y_max-1)
00213 if density_map[rand_X][rand_Y] == 1:
00214 density_map[rand_X][rand_Y] = 0
00215 surplus -= 1
00216
00217 def countCells(density_map):
00218
00219 total_cells = 0
00220 for cell in density_map.flat:
00221 total_cells += cell
00222 return total_cells
00223
00224 if __name__ == '__main__':
00225
00226
00227 rospy.init_node("seed_mea")
00228
00229
00230 soma_dia = 30
00231 dish_width = 2500
00232 dendrite_max = 180
00233
00234 axon_growth = 220
00235
00236 axon_max = dish_width
00237
00238 survival_rate = 65
00239
00240 connectivity_rate = 55
00241
00242 cell_density = 900
00243
00244
00245
00246 cells_per_edge = int(dish_width/soma_dia)
00247
00248
00249 edge_len = nextPowTwo(cells_per_edge) + 1
00250
00251
00252 density_map = np.zeros((edge_len, edge_len))
00253 genPCell(density_map)
00254 renderMap(density_map, "Plasma")
00255
00256
00257
00258
00259 for row in xrange(edge_len):
00260 for col in xrange(edge_len):
00261 if random.random() < density_map[row][col]:
00262 density_map[row][col] = 1
00263 else:
00264 density_map[row][col] = 0
00265 renderMap(density_map, "Cells")
00266
00267
00268
00269 expected_cells = (dish_width/1000)**2 * cell_density
00270 densityReap(density_map, expected_cells)
00271 renderMap(density_map, "Density Corrected")
00272
00273
00274
00275 grimReap(density_map, survival_rate)
00276 renderMap(density_map, "Cull the Weak")
00277
00278
00279
00280
00281 print "Cells remaining:", countCells(density_map)
00282
00283
00284
00285 print "Building connectivity...",
00286 neuron_list = []
00287 neuron_id = 0
00288 for row_1 in xrange(edge_len):
00289 for col_1 in xrange(edge_len):
00290 if density_map[row_1][col_1] == 1:
00291
00292
00293 neuron_list.append(((row_1, col_1), neuron_id))
00294 neuron_id += 1
00295
00296
00297 conn_list = []
00298 for from_neuron in neuron_list:
00299 for to_neuron in neuron_list:
00300
00301 distance = math.sqrt((from_neuron[0][0] - to_neuron[0][0])**2 + (from_neuron[0][1] - to_neuron[0][1])**2)
00302 distance *= soma_dia
00303 if random.random() < gaussConnect(distance, axon_growth):
00304
00305 conn_list.append((from_neuron[1], to_neuron[1]))
00306
00307 print "done."
00308
00309
00310 print "Saving connectivity...",
00311 now = datetime.datetime.now()
00312 file_date = "{0}-{1}-{2}-{3}:{4}:{5}".format(now.year, now.month, now.day, now.hour, now.minute, now.second)
00313
00314
00315 conn_graph = nx.DiGraph()
00316 for connection in conn_list:
00317 conn_graph.add_edge(connection[0], connection[1])
00318
00319
00320 with open("nx_graph_{0}.pickle".format(file_date), "w") as outfile:
00321 Pickler(outfile, 0).dump(conn_graph)
00322 outfile.close()
00323
00324
00325 with open("connections_{0}.pickle".format(file_date), "w") as outfile:
00326 Pickler(outfile, 0).dump(conn_list)
00327 outfile.close()
00328
00329 print "done."
00330
00331
00332
00333
00334 eqs = '''
00335 dv/dt = (ge+gi-(v+49*mV))/(20*ms) : volt
00336 dge/dt = -ge/(5*ms) : volt
00337 dgi/dt = -gi/(10*ms) : volt
00338 '''
00339
00340
00341 neuron_count = int(countCells(density_map))
00342 P = NeuronGroup(neuron_count, eqs, threshold=-50*mV, reset=-60*mV)
00343 P.v = -60*mV + 15 * mV * rand(len(P))
00344
00345
00346 excitory_count = int(neuron_count * 0.75)
00347 inhib_count = neuron_count - excitory_count
00348
00349
00350
00351
00352
00353
00354 inhib_neurons = random.sample(xrange(neuron_count), inhib_count)
00355 Ce = Connection (P, P, 'ge')
00356 Ci = Connection (P, P, 'gi')
00357 for connection in conn_list:
00358 if connection[0] in inhib_neurons:
00359
00360 Ci[connection[0], connection[1]] = -9*mV
00361 else:
00362
00363 Ce[connection[0], connection[1]] = 1.62*mV
00364
00365
00366
00367
00368 pad_rows = 8
00369 pad_cols = 8
00370 ignore_corners = True
00371 pad_dia = 30
00372 pad_spacing = 200
00373 pad_threshold = 40
00374
00375
00376
00377
00378 pad_neuron_map = {}
00379 for pad_x in xrange(0,pad_rows):
00380 for pad_y in xrange (0,pad_cols):
00381 if ignore_corners:
00382 if pad_x == 0 and pad_y == 0:
00383 continue
00384 elif pad_x == 0 and pad_y == (pad_cols - 1):
00385 continue
00386 elif pad_x == (pad_rows - 1) and pad_y == 0:
00387 continue
00388 elif pad_x == (pad_rows - 1) and pad_y == (pad_cols - 1):
00389 continue
00390
00391
00392 pad_x_loc = pad_x * pad_spacing
00393 pad_y_loc = pad_y * pad_spacing
00394
00395
00396 close_neurons = Channel()
00397 for neuron in neuron_list:
00398
00399 neuron_x_loc = neuron[0][0] * soma_dia
00400 neuron_y_loc = neuron[0][1] * soma_dia
00401
00402 dist = math.sqrt((neuron_x_loc - pad_x_loc)**2 + (neuron_y_loc - pad_y_loc)**2)
00403
00404 if dist < pad_threshold:
00405
00406 close_neurons.add(CloseNeuron(neuron[1], dist))
00407
00408 if close_neurons.size() == 0:
00409 pad_neuron_map[(pad_x, pad_y)] = None
00410 print '(' + str(pad_x) + ',' + str(pad_y) + '): None'
00411 else:
00412 pad_neuron_map[(pad_x, pad_y)] = close_neurons
00413 print '(' + str(pad_x) + ',' + str(pad_y) + '):' + str(close_neurons)
00414
00415
00416
00417 with open("pad_{0}.pickle".format(file_date), "w") as outfile:
00418 Pickler(outfile, 0).dump(pad_neuron_map)
00419 outfile.close()
00420
00421 print "done."