-
Notifications
You must be signed in to change notification settings - Fork 4
/
Copy pathdark_room_to_saliency.py
51 lines (43 loc) · 2.31 KB
/
dark_room_to_saliency.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
import rospy
from sensor_msgs.msg import Image
from geometry_msgs.msg import Point
from cv_bridge import CvBridge
from attention import Saliency
from std_msgs.msg import Float32MultiArray
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'))
@nrp.MapVariable("saliency", initial_value = Saliency(tensorflow_path, model_file, network_input_height, network_input_width, False))
@nrp.MapVariable("saliency_pub", initial_value = rospy.Publisher("/saliency_map", Float32MultiArray, 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("elapsed", initial_value = 0)
@nrp.MapVariable("saliency_map", initial_value = None)
@nrp.MapRobotSubscriber("image", Topic('/icub_model/left_eye_camera/image_raw', sensor_msgs.msg.Image))
def image_to_saliency(t, saliency, saliency_pub, saliency_image_pub, bridge, image, last_time, elapsed, saliency_map):
if image.value is None:
return
if last_time.value is None:
last_time.value = t
current_time = t
dt = current_time - last_time.value
last_time.value = current_time
elapsed.value = elapsed.value + dt
if elapsed.value < 0.01:
return
else:
elapsed.value = 0.
if saliency_map.value is None:
image = bridge.value.imgmsg_to_cv2(image.value, "bgr8")
image = np.zeros(image.shape)
saliency_map.value = saliency.value.compute_saliency_map(image)
saliency_map_image = bridge.value.cv2_to_imgmsg(np.uint8(saliency_map.value * 255.), "mono8")
saliency_image_pub.value.publish(saliency_map_image)
from std_msgs.msg import Float32MultiArray, MultiArrayDimension, MultiArrayLayout
height = MultiArrayDimension(size=len(saliency_map.value))
width = MultiArrayDimension(size=len(saliency_map.value[0]))
lo = MultiArrayLayout([height, width], 0)
saliency_pub.value.publish(Float32MultiArray(layout=lo, data=saliency_map.value.flatten()))
return