assembler_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 import threading
41 from time import sleep
42 from sensor_msgs.msg import LaserScan
43 from pr2_msgs import LaserScannerSignal
44 from mechanism_msgs.msg import MechanismState
45 from std_msgs.msg import *
46 from dense_laser_assembler.msg import *
48 from dense_laser_assembler.dense_laser_cache import DenseLaserCache
49 from sensor_msgs.msg import *
50 
51 # Globals
52 laser_cache = [ ]
53 first_signal = True
54 prev_signal_time = [ ]
55 image_pub = [ ]
56 test_pub = [ ]
57 
58 
59 def scan_callback(msg) :
60  req_lock.acquire()
61  laser_cache.add_scan(msg)
62  laser_cache.process_scans()
63  laser_cache.process_interval_reqs()
64  req_lock.release()
65 
66 def mech_callback(msg) :
67  req_lock.acquire()
68  laser_cache.add_mech_state(msg)
69  laser_cache.process_scans()
70  laser_cache.process_interval_reqs()
71  req_lock.release()
72 
73 def signal_callback(msg) :
74  req_lock.acquire()
75  global first_signal
76  global prev_signal
77  laser_cache.process_scans()
78  if first_signal :
79  first_signal = False
80  else :
81  laser_cache.add_interval_req(prev_signal.header.stamp, msg.header.stamp)
82  laser_cache.process_interval_reqs()
83  prev_signal = msg
84  print('Got signal message!')
85  print(' Signal=%i' % msg.signal)
86  req_lock.release()
87 
89 
90  # Check data consistency
91  if (len(scans) == 0) :
92  print('Processed interval with no scans. Not publishing')
93  return
94 
95  rows = len(scans)
96  cols = len(scans[0].scan.ranges)
97  if any( [len(x.scan.ranges) != cols for x in scans] ) or any( [len(x.scan.intensities) != cols for x in scans]) :
98  print("# Readings aren't consistent across interval")
99  return
100 
101 
102  print('About to process cloud with %u scans' % len(scans))
103 
104  # Sort by tilting joint angle
105  sorted_scans = sorted(scans, lambda x,y:cmp(x.pos[0],y.pos[0]))
106 
107 
108  msg_header = rospy.Header()
109  msg_header.stamp = scans[-1].scan.header.stamp
110  msg_header.frame_id = scans[-1].scan.header.frame_id
111 
112  layout = MultiArrayLayout([ MultiArrayDimension('rows', rows, rows*cols),
113  MultiArrayDimension('cols', cols, cols),
114  MultiArrayDimension('elem', 1, 1) ], 0 )
115  # Build the messages in a reasonable ROS format
116  intensity_msg = Float32MultiArrayStamped()
117  range_msg = Float32MultiArrayStamped()
118  info_msg = scans[-1].scan
119  joint_msg = Float32MultiArrayStamped()
120 
121  intensity_msg.header = msg_header
122  range_msg.header = msg_header
123  joint_msg.header = msg_header
124 
125  intensity_msg.data.layout = layout
126  range_msg.data.layout = layout
127  joint_msg.data.layout = MultiArrayLayout([ MultiArrayDimension('rows', rows, rows*2),
128  MultiArrayDimension('cols', 2, 2),
129  MultiArrayDimension('elem', 1, 1) ], 0 )
130  #joint_msg.data.layout = layout
131 
132  # Clear out data from the info message. (Keep everything except intensity and range data)
133  #info_msg.ranges = [ ]
134  #info_msg.intensities = [ ]
135 
136  # Populate intensities & ranges
137  intensity_msg.data.data = []
138  range_msg.data.data = []
139  for x in sorted_scans :
140  intensity_msg.data.data.extend(x.scan.intensities)
141  range_msg.data.data.extend(x.scan.ranges)
142  joint_msg.data.data.extend(x.pos)
143 
144  intensity_pub.publish(intensity_msg)
145  range_pub.publish(range_msg)
146  info_pub.publish(info_msg)
147  joint_pos_pub.publish(joint_msg)
148 
149  #image = sensor_msgs.msg.Image()
150 
151  #image.header = msg_header
152  #image.label = 'intensity'
153  #image.encoding = 'mono'
154  #image.depth = 'uint8'
155  #max_val = max(joint_msg.data.data)
156  #min_val = min(joint_msg.data.data)
157  #image.uint8_data.data = "".join([chr(int(255*x/max_val)) for x in intensity_msg.data.data])
158  #image.uint8_data.data = "".join([chr(int(255*(x-min_val)/(max_val-min_val))) for x in joint_msg.data.data])
159  #image.uint8_data.data = ''
160  #image.uint8_data.layout = intensity_msg.data.layout
161  #image_pub.publish(image)
162 
163 
164  print(' Processed cloud with %u rays' % len(intensity_msg.data.data))
165 
166 if __name__ == '__main__':
167 
168  req_lock = threading.Lock()
169 
170  print('Initializing DenseLaserCache')
171  laser_cache = DenseLaserCache(interval_req_callback, 200, 1000, 100) ;
172  print('Done initializing')
173 
174  rospy.init_node('dense_assembler', anonymous=False)
175  signal_sub = rospy.Subscriber("laser_tilt_controller/laser_scanner_signal",
176  LaserScannerSignal, signal_callback)
177 
178  intensity_pub = rospy.Publisher("dense_tilt_scan/intensity", Float32MultiArrayStamped)
179  range_pub = rospy.Publisher("dense_tilt_scan/range", Float32MultiArrayStamped)
180  info_pub = rospy.Publisher("dense_tilt_scan/scan_info", LaserScan)
181  joint_pos_pub = rospy.Publisher("dense_tilt_scan/joint_info",Float32MultiArrayStamped)
182  #image_pub = rospy.Publisher("test_image", Image)
183 
184  scan_sub = rospy.Subscriber("tilt_scan", LaserScan, scan_callback)
185 
186  mech_sub = rospy.Subscriber("mechanism_state", MechanismState, mech_callback)
187 
188  rospy.spin()
def scan_callback(msg)
def mech_callback(msg)
def signal_callback(msg)
def interval_req_callback(scans)


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