37 import roslib; roslib.load_manifest(
'dense_laser_assembler')
40 from time
import sleep
53 lower_lim = max_val*0.0
54 upper_lim = max_val*1.0
60 elif a > upper_lim -lower_lim :
63 return chr(int((2**8-1)*a/(upper_lim-lower_lim)))
66 image = sensor_msgs.msg.Image()
67 image.header = msg.header
68 image.label =
'intensity' 69 image.encoding =
'mono' 71 max_val = max(msg.data.data)
73 image.uint8_data.data =
"".join([
rescale(x,max_val)
for x
in msg.data.data])
74 image.uint8_data.layout = msg.data.layout
75 intensity_pub.publish(image)
78 image = sensor_msgs.msg.Image()
79 image.header = msg.header
81 image.encoding =
'mono' 83 max_val = max(msg.data.data)
84 image.uint8_data.data =
"".join([chr(int((2**8-1)*x/max_val))
for x
in msg.data.data])
85 image.uint8_data.layout = msg.data.layout
86 range_pub.publish(image)
88 if __name__ ==
'__main__':
90 rospy.init_node(
'laser_imager', anonymous=
False)
92 intensity_pub = rospy.Publisher(
"dense_tilt_scan/intensity_image", Image)
93 range_pub = rospy.Publisher(
"dense_tilt_scan/range_image", Image)
95 intensity_sub = rospy.Subscriber(
"dense_tilt_scan/intensity", Float32MultiArrayStamped, intensity_callback)
96 range_sub = rospy.Subscriber(
"dense_tilt_scan/range", Float32MultiArrayStamped, range_callback)
def intensity_callback(msg)