Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
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 import roslib; roslib.load_manifest('dense_laser_assembler') 
00038 import sys
00039 import rospy
00040 from time import sleep
00041 from laser_scan.msg import *
00042 from std_msgs.msg import *
00043 from dense_laser_assembler.msg import *
00044 from pr2_mechanism_controllers.msg import *
00045 from sensor_msgs.msg import Image
00046 
00047 
00048 
00049 
00050 
00051 
00052 def rescale(x, max_val) :
00053     lower_lim = max_val*0.0
00054     upper_lim = max_val*1.0
00055     
00056     
00057     a = x - lower_lim
00058     if a <= 0 :
00059         return chr(0)
00060     elif a > upper_lim -lower_lim :
00061         return chr(255)
00062     
00063     return chr(int((2**8-1)*a/(upper_lim-lower_lim)))
00064 
00065 def intensity_callback(msg) :
00066     image = sensor_msgs.msg.Image()
00067     image.header = msg.header
00068     image.label  = 'intensity'
00069     image.encoding = 'mono'
00070     image.depth = 'uint8'
00071     max_val = max(msg.data.data)
00072     
00073     image.uint8_data.data   = "".join([rescale(x,max_val) for x in msg.data.data])
00074     image.uint8_data.layout = msg.data.layout
00075     intensity_pub.publish(image)
00076 
00077 def range_callback(msg) :
00078     image = sensor_msgs.msg.Image()
00079     image.header = msg.header
00080     image.label  = 'range'
00081     image.encoding = 'mono'
00082     image.depth = 'uint8'
00083     max_val = max(msg.data.data)
00084     image.uint8_data.data   = "".join([chr(int((2**8-1)*x/max_val)) for x in msg.data.data])
00085     image.uint8_data.layout = msg.data.layout
00086     range_pub.publish(image)
00087 
00088 if __name__ == '__main__':
00089 
00090     rospy.init_node('laser_imager', anonymous=False)
00091 
00092     intensity_pub = rospy.Publisher("dense_tilt_scan/intensity_image", Image)
00093     range_pub     = rospy.Publisher("dense_tilt_scan/range_image",     Image)
00094     
00095     intensity_sub = rospy.Subscriber("dense_tilt_scan/intensity", Float32MultiArrayStamped, intensity_callback)
00096     range_sub     = rospy.Subscriber("dense_tilt_scan/range",     Float32MultiArrayStamped, range_callback)
00097 
00098     rospy.spin()