def __init__(self): self.saccade = Saccade() self.saliency_sub = rospy.Subscriber("/saliency_map", Float32MultiArray, self.saliency_map_callback, queue_size=1, buff_size=2**24) self.saccade_target_pub = rospy.Publisher("/saccade_target", Point, queue_size=1) self.saccade_potential_target_pub = rospy.Publisher( "/saccade_potential_target", Point, queue_size=1) self.visual_neurons_pub = rospy.Publisher("/visual_neurons", Image, queue_size=1) self.motor_neurons_pub = rospy.Publisher("/motor_neurons", Image, queue_size=1) self.reset_saccade_serv = rospy.Service('/reset_saccade', ResetSaccade, self.handle_reset_saccade) self.shift_serv = rospy.Service('/shift', Empty, self.handle_shift) self.last_time = None self.cv_bridge = CvBridge() self.saliency_map = None
def simulate(sol, n_it, i): print(datetime.datetime.now()) params = x_to_params(sol) np.random.seed(args.seed) saccade = Saccade(**params) time = 0 all_targets = [] all_times = [] while time < time_limit: (target, is_actual_target) = saccade.compute_saccade_target(saliency_map, dt=dt) if is_actual_target: all_targets.append(target) all_times.append(time) time += dt rate = len(all_targets) * 1000. / time_limit error = gt_mean_rate - rate print("Solution {} has rate: {}. Error: {}".format(params, rate, error)) return error
def simulate(sol, n_it, i, time_limit=5000): params = x_to_params(sol) all_errors = [] all_rates = [] for sal in saliency_maps: np.random.seed(args.seed) saccade = Saccade(**params) time = 0 all_times = [] score_img = np.zeros_like(sal) radius_rf = 5 while time < time_limit: (target, is_actual_target) = saccade.compute_saccade_target(sal, dt=dt) if is_actual_target: rr, cc = circle(target[1], target[0], radius=args.rf_radius_score, shape=score_img.shape) score_img[rr, cc] = sal[rr, cc] all_times.append(time) time += dt rate = len(all_times) * 1000. / time_limit # we want score to be big with few saccades if len(all_times) == 0: # strongly penalize when no saccades are made reg = 100 else: reg = rate error = -score_img.sum() + np.exp(reg * 0.5) all_errors.append(error) all_rates.append(rate) print("Solution {} has rates: {}. Error: {}".format( params, all_rates, sum(all_errors))) return sum(all_errors)
model_file = args.model saliency = Saliency(model_file=model_file) image = misc.imread(args.image) saliency_map = saliency.compute_saliency_map(image) plt.imsave(path.join(args.out, 'saliency.png'), saliency_map, cmap=plt.get_cmap('gray')) dt = 5. first_saccades = np.zeros((rf_amps.size, rf_stds.size)) all_targets = { std: [] for std in rf_stds } time_limit = 800. fig = plt.figure() for i, amp in enumerate(rf_amps): for j, std in enumerate(rf_stds): np.random.seed(args.seed) saccade = Saccade(amp_rf=amp, sig_rf=std) ax = fig.add_subplot(111) if i == 0: rf_id = (saccade.Ns + 1) * saccade.Ns / 2 plot_rf(saccade.receptive_fields[rf_id].reshape(saccade.Ns, saccade.Ns), std, args.out) is_actual_target = False time = 0 while not is_actual_target and time < time_limit: (target, is_actual_target) = saccade.compute_saccade_target(saliency_map, dt=dt) time += dt print("receptive field with amp {:.3f} std {:.3f} took {}ms. {} <= motor <= {}" .format(amp, std, int(time), saccade.motor_neurons.min(), saccade.motor_neurons.max())) first_saccades[i, j] = time if is_actual_target: all_targets[std].append(target)
c=all_times, s=50, cmap=plt.get_cmap('Reds')) plt.savefig(path.join(out, 'targets.png'), dpi=150) def draw_rf(ax, rf): return ax.imshow(np.max(rf, axis=0), aspect='equal', cmap=plt.get_cmap('Reds'), interpolation='bilinear', vmin=0, vmax=1.) saccade = Saccade(modulation_type=args.rf_modulation_type) ims = [] dt = 5 simulation_time = 1000 fig, (ax1, ax2, ax3) = plt.subplots(1, 3) ax1.set_title('visual neurons') ax2.set_title('motor neurons') ax3.set_title('receptive fields') all_targets = [] all_times = [] time = 0 neuron_min = -3 neuron_max = saccade.theta epsilon = 5
def reset_callback(t, saccade, reset): from attention import Saccade saccade.value = Saccade() return
from attention import Saccade from std_msgs.msg import Empty @nrp.MapVariable("saccade", initial_value=Saccade(), scope=nrp.GLOBAL) @nrp.MapRobotSubscriber("reset", Topic("/reset", Empty)) @nrp.Neuron2Robot(triggers="reset") def reset_callback(t, saccade, reset): from attention import Saccade saccade.value = Saccade() return
def handle_reset_saccade(self, req): rospy.loginfo("Resetting node") self.saccade = Saccade() return True
class SaccadeNode(): def __init__(self): self.saccade = Saccade() self.saliency_sub = rospy.Subscriber("/saliency_map", Float32MultiArray, self.saliency_map_callback, queue_size=1, buff_size=2**24) self.saccade_target_pub = rospy.Publisher("/saccade_target", Point, queue_size=1) self.saccade_potential_target_pub = rospy.Publisher( "/saccade_potential_target", Point, queue_size=1) self.visual_neurons_pub = rospy.Publisher("/visual_neurons", Image, queue_size=1) self.motor_neurons_pub = rospy.Publisher("/motor_neurons", Image, queue_size=1) self.reset_saccade_serv = rospy.Service('/reset_saccade', ResetSaccade, self.handle_reset_saccade) self.shift_serv = rospy.Service('/shift', Empty, self.handle_shift) self.last_time = None self.cv_bridge = CvBridge() self.saliency_map = None def saliency_map_callback(self, saliency_map): rospy.loginfo("Saliency_map updated") lo = saliency_map.layout self.saliency_map = np.asarray( saliency_map.data[lo.data_offset:]).reshape( lo.dim[0].size, lo.dim[1].size) def handle_reset_saccade(self, req): rospy.loginfo("Resetting node") self.saccade = Saccade() return True def handle_shift(self, req): rospy.loginfo("Shifting activity") self.saccade.shift() return def loop(self): hz = 1000. # 10000 would be perfect rate = rospy.Rate(hz) while not rospy.is_shutdown(): if self.saliency_map is None: continue (target, is_actual_target, visual_neurons, motor_neurons) = self.saccade.compute_saccade_target( self.saliency_map, 1. / hz * 1000.) self.saccade_potential_target_pub.publish(Point(*target)) if is_actual_target: self.saccade_target_pub.publish(Point(*target)) visual_neurons = (visual_neurons - visual_neurons.min()) / ( visual_neurons.max() - visual_neurons.min()) motor_neurons = (motor_neurons - motor_neurons.min()) / ( motor_neurons.max() - motor_neurons.min()) try: visual_neurons_image = self.cv_bridge.cv2_to_imgmsg( np.uint8(visual_neurons * 255.), "mono8") motor_neurons_image = self.cv_bridge.cv2_to_imgmsg( np.uint8(motor_neurons * 255.), "mono8") except CvBridgeError as e: print e self.visual_neurons_pub.publish(visual_neurons_image) self.motor_neurons_pub.publish(motor_neurons_image) rate.sleep()
from attention import Saccade from rosgraph_msgs.msg import Clock from std_msgs.msg import Float32MultiArray from sensor_msgs.msg import Image from embodied_attention.srv import Target @nrp.MapVariable("saccade", initial_value=Saccade( sig_lat=0.067047852, sig_rf=0.19616042775, sig_IoR=0.17097546900000002, amp_lat=0.0005232999299999999, amp_rf=0.01567661064, amp_IoR=2.5476048149999997, amp_noise=0.1257144138, k=0.029415594360000002, g=0.35788331370000004, theta=4.31359962, tau=99.701898, tau_mod=99.701898, sig_mod=0.19616042775, modulation_type='none', ), scope=nrp.GLOBAL) @nrp.MapVariable("target_pub", initial_value=rospy.Publisher("/saccade_target", Point, queue_size=1)) @nrp.MapVariable("potential_target_pub", initial_value=rospy.Publisher("/saccade_potential_target", Point,
# cmaes_best = [0.73303171, 0.40036918, 1.61391472, 1.05752332, 0.98779811, 1.99986595, 1.17318613, 1.75298134, 0.09770866, 0.4222649 , 1.99960248] # cmaes_best = [0.67047852, 0.73468325, 1.70975469, 0.52329993, 1.95957633, 1.69840321, 1.39682682, 1.73032908, 1.08449489, 0.71893327, 1.99403796] cmaes_best = [1.22719931, 0.66935663, 1.78590383, 0.2920052, 1.99979222, 1.61678862, 1.07153312, 1.96586086, 0.01860188, 1.3752726, 1.50149685] # convert the cmaes params to the full state x by inserting static params def x_to_params(param_scaling): params = saccade_params.copy() for i, p in enumerate(optimize_params): params[p] = params[p] * param_scaling[i] params['tau_mod'] = params['tau'] params['sig_mod'] = params['sig_rf'] return params best_saccade_params = x_to_params(cmaes_best) print("Saccade params:\n{}".format(best_saccade_params)) saccade = Saccade(**best_saccade_params) ims = [] dt = 5 simulation_time = 1000 fig, (ax1, ax2, ax3) = plt.subplots(1, 3) ax1.set_title('visual neurons') ax2.set_title('motor neurons') ax3.set_title('receptive fields') all_targets = [] all_times = [] time = 0 neuron_min = -3 neuron_max = saccade.theta epsilon = 5
from attention import Saliency, Saccade tensorflow_path = rospy.get_param( "~tensorflow_path", "/opt/tensorflow_venv/lib/python2.7/site-packages") model_file = rospy.get_param('~saliency_file', '/tmp/model.ckpt') network_input_height = float(rospy.get_param('~network_input_height', '192')) network_input_width = float(rospy.get_param('~network_input_width', '256')) shift_activity = bool(rospy.get_param('~shift_activity', 'True')) @nrp.MapVariable("saliency", initial_value=Saliency(tensorflow_path, model_file, network_input_height, network_input_width)) @nrp.MapVariable("saccade", initial_value=Saccade(shift_activity)) @nrp.MapVariable("target_pub", initial_value=rospy.Publisher("/saccade_target", Point, queue_size=1)) @nrp.MapVariable("potential_target_pub", initial_value=rospy.Publisher("/saccade_potential_target", Point, queue_size=1)) @nrp.MapVariable("saliency_image_pub", initial_value=rospy.Publisher("/saliency_map_image", Image, queue_size=1)) @nrp.MapVariable("bridge", initial_value=CvBridge()) @nrp.MapVariable("last_time", initial_value=None) @nrp.MapVariable("points", initial_value=[], scope=nrp.GLOBAL)