laser_image_node.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2008, Willow Garage, Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of Willow Garage, Inc. nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #
35 
36 
37 import roslib; roslib.load_manifest('dense_laser_assembler')
38 import sys
39 import rospy
40 from time import sleep
41 from laser_scan.msg import *
42 from std_msgs.msg import *
43 from dense_laser_assembler.msg import *
45 from sensor_msgs.msg import Image
46 
47 
48 # Takes the dense laser scan data and converts it into images to can be viewed in
49 # image_view. Generally used as a debugging tool.
50 
51 
52 def rescale(x, max_val) :
53  lower_lim = max_val*0.0
54  upper_lim = max_val*1.0
55  #lower_lim = 2000
56  #upper_lim = 3000
57  a = x - lower_lim
58  if a <= 0 :
59  return chr(0)
60  elif a > upper_lim -lower_lim :
61  return chr(255)
62 
63  return chr(int((2**8-1)*a/(upper_lim-lower_lim)))
64 
66  image = sensor_msgs.msg.Image()
67  image.header = msg.header
68  image.label = 'intensity'
69  image.encoding = 'mono'
70  image.depth = 'uint8'
71  max_val = max(msg.data.data)
72  #image.uint8_data.data = "".join([chr(int((2**8-1)*x/max_val)) for x in 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)
76 
77 def range_callback(msg) :
78  image = sensor_msgs.msg.Image()
79  image.header = msg.header
80  image.label = 'range'
81  image.encoding = 'mono'
82  image.depth = 'uint8'
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)
87 
88 if __name__ == '__main__':
89 
90  rospy.init_node('laser_imager', anonymous=False)
91 
92  intensity_pub = rospy.Publisher("dense_tilt_scan/intensity_image", Image)
93  range_pub = rospy.Publisher("dense_tilt_scan/range_image", Image)
94 
95  intensity_sub = rospy.Subscriber("dense_tilt_scan/intensity", Float32MultiArrayStamped, intensity_callback)
96  range_sub = rospy.Subscriber("dense_tilt_scan/range", Float32MultiArrayStamped, range_callback)
97 
98  rospy.spin()
def intensity_callback(msg)
def rescale(x, max_val)


dense_laser_assembler
Author(s): Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:50:54