9 from geometry_msgs.msg
import Twist
10 from sensor_msgs.msg
import LaserScan
11 from collections
import deque
16 reduce rplidar scan from 360° to 180° 20 rospy.init_node(
'xbot_scan180')
21 self.
pub = rospy.Publisher(
'/scan', LaserScan, queue_size=1)
22 rospy.Subscriber(
"/rplidar_scan", LaserScan, self.
scan_dataCB)
24 while not rospy.is_shutdown():
29 scan_data.ranges =
list(scan_data.ranges)
30 for i
in xrange(len(scan_data.ranges)):
31 if i < 90
or i >= 270:
32 scan_data.ranges[i] = float(
'inf')
33 scan_data.ranges =
tuple(scan_data.ranges)
34 self.pub.publish(scan_data)
37 if __name__ ==
'__main__':
39 rospy.loginfo(
"initialization system")
41 rospy.loginfo(
"process done and quit")
42 except rospy.ROSInterruptException:
43 rospy.loginfo(
"xbot_scan180 terminated.")
def scan_dataCB(self, scan_data)