Go to the documentation of this file.00001
00002
00003 '''
00004 brian_recv.py
00005 Copyright 2013 University of Massachusetts Lowell
00006 Author: Jonathan Hasenzahl, Abraham Shultz
00007 '''
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 import roslib; roslib.load_manifest('neuro_recv')
00021 import rospy
00022 from neuro_recv.msg import dish_state
00023 from brian import *
00024 from pickle import Unpickler
00025 import random
00026
00027
00028
00029
00030 class BrianSimulation():
00031 def __init__(self, connections, channels):
00032 self.connections = connections
00033 self.channels = channels
00034
00035
00036 self.getParams()
00037
00038
00039 self.initPubs()
00040
00041
00042 self.runSimulation()
00043
00044
00045 self.publishBuffer()
00046
00047
00048 self.offset = rospy.Time.now() - rospy.Time(0)
00049
00050
00051 self.publish()
00052
00053
00054 def getParams(self):
00055
00056 try:
00057 self.running_time = rospy.get_param('brian_running_time')
00058 except KeyError:
00059 rospy.logerr('Could not get brian_running_time parameter, default is 30.0')
00060 self.running_time = 30.0
00061
00062
00063 try:
00064 self.do_volt_distr = rospy.get_param('do_volt_distr')
00065 except KeyError:
00066 rospy.logerr('Could not get do_volt_distr parameter, default is True')
00067 self.do_volt_distr = True
00068
00069
00070 try:
00071 self.do_burst_calc = rospy.get_param('do_burst_calc')
00072 except KeyError:
00073 rospy.logerr('Could not get do_burst_calc parameter, default is True')
00074 self.do_burst_calc = True
00075
00076
00077 try:
00078 self.buffer_size = rospy.get_param('buffer_size')
00079 except KeyError:
00080 rospy.logerr('Could not get buffer_size parameter, default is 1000')
00081 self.buffer_size = 1000
00082
00083
00084 try:
00085 self.loop_rate = rospy.get_param('loop_rate')
00086 except KeyError:
00087 rospy.logerr('Could not get loop_rate parameter, default is 200')
00088 self.loop_rate = 200
00089
00090
00091 def initPubs(self):
00092 rospy.loginfo('Waiting for subscribers...')
00093
00094 if self.do_volt_distr == True:
00095
00096 self.dish_pub_volt = rospy.Publisher('dish_states_to_volt_distr', dish_state)
00097 while self.dish_pub_volt.get_num_connections() < 1 and not rospy.is_shutdown():
00098 pass
00099
00100 if self.do_burst_calc == True:
00101
00102 self.dish_pub_viz = rospy.Publisher('dish_states_to_dish_viz', dish_state)
00103 self.dish_pub_burst = rospy.Publisher('dish_states_to_burst_creator', dish_state)
00104 while self.dish_pub_viz.get_num_connections() < 1 and self.dish_pub_burst.get_num_connections() < 1 and not rospy.is_shutdown():
00105 pass
00106
00107
00108 def runSimulation(self):
00109
00110 eqs = Equations('''
00111 dv/dt = (ge+gi-(v+49*mV))/(20*ms) : volt
00112 dge/dt = -ge/(5*ms) : volt
00113 dgi/dt = -gi/(10*ms) : volt
00114 ''')
00115
00116
00117
00118
00119 neuron_count = self.connections[-1][0] + 1
00120
00121
00122 P = NeuronGroup(neuron_count, eqs, threshold=-50*mV, reset=-60*mV)
00123 P.v = -60*mV + (15 * rand(len(P))) * mV
00124
00125
00126 excitory_count = int(neuron_count * 0.75)
00127 inhib_count = neuron_count - excitory_count
00128
00129
00130
00131
00132
00133
00134 inhib_neurons = random.sample(xrange(neuron_count), inhib_count)
00135 Ce = Connection (P, P, 'ge')
00136 Ci = Connection (P, P, 'gi')
00137 for connection in self.connections:
00138 prune = random.randint(0,100)
00139
00140 if connection[0] in inhib_neurons:
00141 Ci[connection[0], connection[1]] = -9*mV
00142 else:
00143 Ce[connection[0], connection[1]] = 1.62*mV
00144
00145
00146
00147 self.recorded_neurons = []
00148 for channel in self.channels:
00149 if channel != None:
00150 for neuron in channel.neurons:
00151 self.recorded_neurons.append(neuron.data)
00152
00153
00154
00155
00156
00157
00158
00159
00160 self.M = StateMonitor(P, "v", record=self.recorded_neurons, timestep=10)
00161
00162
00163
00164 rospy.loginfo("Running simulation...")
00165 run(self.running_time * second)
00166 rospy.loginfo("Simulation finished")
00167
00168
00169 def publishBuffer(self):
00170 rospy.loginfo("Publishing buffer dishes...")
00171 loop_rate = rospy.Rate(self.loop_rate)
00172
00173 for current_dish in range(self.buffer_size):
00174
00175 d = dish_state()
00176
00177
00178 for channel in range(60):
00179 d.samples[channel] = 0.0
00180
00181
00182
00183
00184 if self.channels[channel] != None:
00185 for neuron in self.channels[channel].neurons:
00186 weight = neuron.weight / self.channels[channel].total_weight
00187 weighted = self.M[neuron.data][current_dish] * weight
00188 d.samples[channel] += weighted
00189
00190
00191
00192
00193
00194 if self.do_burst_calc == True:
00195 self.dish_pub_burst.publish(d)
00196 loop_rate.sleep()
00197
00198
00199 def publish(self):
00200 rospy.loginfo("Publishing dishes...")
00201 loop_rate = rospy.Rate(self.loop_rate)
00202 current_dish = self.buffer_size
00203
00204 while current_dish < len(self.M[self.recorded_neurons[0]]) and not rospy.is_shutdown():
00205
00206 d = dish_state()
00207
00208
00209 for channel in range(60):
00210 d.samples[channel] = 0.0
00211
00212
00213
00214
00215 if self.channels[channel] != None:
00216 for neuron in self.channels[channel].neurons:
00217 weight = neuron.weight / self.channels[channel].total_weight
00218 weighted = self.M[neuron.data][current_dish] * weight
00219 d.samples[channel] += weighted
00220
00221
00222
00223
00224 d.header.stamp = rospy.Time.now() - self.offset
00225
00226
00227 if self.do_volt_distr == True:
00228 self.dish_pub_volt.publish(d)
00229 if self.do_burst_calc == True:
00230 self.dish_pub_burst.publish(d)
00231 self.dish_pub_viz.publish(d)
00232
00233
00234 current_dish += 1
00235 loop_rate.sleep()
00236
00237
00238 end = dish_state()
00239 end.last_dish = True
00240 if self.do_volt_distr == True:
00241 self.dish_pub_volt.publish(end)
00242 if self.do_burst_calc == True:
00243 self.dish_pub_burst.publish(end)
00244
00245 rospy.loginfo('Publishing finished')
00246
00247
00248
00249
00250
00251 class Channel():
00252 def __init__(self):
00253 self.neurons = []
00254 self.total_weight = 0.0
00255
00256 def __str__(self):
00257 name = 'Weight:' + str(self.total_weight)
00258 if len(self.neurons) == 0:
00259 name += '[No neurons]'
00260 else:
00261 for neuron in self.neurons:
00262 name += '[' + str(neuron) + ']'
00263 return name
00264
00265 def add(self, neuron):
00266 self.neurons.append(neuron)
00267 self.total_weight += neuron.weight
00268
00269 def size(self):
00270 return len(self.neurons)
00271
00272
00273
00274
00275
00276 class CloseNeuron():
00277 def __init__(self, data, dist):
00278 self.data = data
00279 self.weight = 40.0 - dist
00280
00281 def __str__(self):
00282 return str(self.data) + ':' + str(self.weight)
00283
00284
00285 def channelizer(pad_neuron_map):
00286 channels = []
00287 for row in range(8):
00288 for col in range(8):
00289 if row == 0 and col == 0:
00290 continue
00291 elif row == 0 and col == 7:
00292 continue
00293 elif row == 7 and col == 0:
00294 continue
00295 elif row == 7 and col == 7:
00296 continue
00297 channels.append(pad_neuron_map[(row, col)])
00298 return channels
00299
00300 if __name__ == '__main__':
00301 rospy.init_node('brian_recv')
00302
00303
00304 try:
00305 connections_file_name = rospy.get_param('brian_connections_file_path')
00306 pad_neuron_map_file_name = rospy.get_param('brian_pad_neuron_map_file_path')
00307 except KeyError:
00308 rospy.logfatal('Could not load file name parameters')
00309 else:
00310
00311 try:
00312 connections_file = open(connections_file_name)
00313 pad_neuron_map_file = open(pad_neuron_map_file_name)
00314 except IOError:
00315 rospy.logfatal('Could not open pickle files')
00316 else:
00317
00318 connections = Unpickler(connections_file).load()
00319 pad_neuron_map = Unpickler(pad_neuron_map_file).load()
00320 connections_file.close()
00321 pad_neuron_map_file.close()
00322
00323
00324 channels = channelizer(pad_neuron_map)
00325
00326
00327 try:
00328 brian = BrianSimulation(connections, channels)
00329 except rospy.ROSInterruptException:
00330 pass