37 import roslib; roslib.load_manifest(
'dense_laser_assembler')
41 from time
import sleep
43 from pr2_msgs
import LaserScannerSignal
44 from mechanism_msgs.msg
import MechanismState
54 prev_signal_time = [ ]
61 laser_cache.add_scan(msg)
62 laser_cache.process_scans()
63 laser_cache.process_interval_reqs()
68 laser_cache.add_mech_state(msg)
69 laser_cache.process_scans()
70 laser_cache.process_interval_reqs()
77 laser_cache.process_scans()
81 laser_cache.add_interval_req(prev_signal.header.stamp, msg.header.stamp)
82 laser_cache.process_interval_reqs()
84 print(
'Got signal message!')
85 print(
' Signal=%i' % msg.signal)
91 if (len(scans) == 0) :
92 print(
'Processed interval with no scans. Not publishing')
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")
102 print(
'About to process cloud with %u scans' % len(scans))
105 sorted_scans = sorted(scans,
lambda x,y:cmp(x.pos[0],y.pos[0]))
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
112 layout = MultiArrayLayout([ MultiArrayDimension(
'rows', rows, rows*cols),
113 MultiArrayDimension(
'cols', cols, cols),
114 MultiArrayDimension(
'elem', 1, 1) ], 0 )
116 intensity_msg = Float32MultiArrayStamped()
117 range_msg = Float32MultiArrayStamped()
118 info_msg = scans[-1].scan
119 joint_msg = Float32MultiArrayStamped()
121 intensity_msg.header = msg_header
122 range_msg.header = msg_header
123 joint_msg.header = msg_header
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 )
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)
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)
164 print(
' Processed cloud with %u rays' % len(intensity_msg.data.data))
166 if __name__ ==
'__main__':
168 req_lock = threading.Lock()
170 print(
'Initializing DenseLaserCache')
172 print(
'Done initializing')
174 rospy.init_node(
'dense_assembler', anonymous=
False)
175 signal_sub = rospy.Subscriber(
"laser_tilt_controller/laser_scanner_signal",
176 LaserScannerSignal, signal_callback)
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)
184 scan_sub = rospy.Subscriber(
"tilt_scan", LaserScan, scan_callback)
186 mech_sub = rospy.Subscriber(
"mechanism_state", MechanismState, mech_callback)
def interval_req_callback(scans)