xbot_scan180.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # coding=utf-8
3 """
4 xbot_safety.py
5 """
6 
7 import rospy
8 import std_msgs.msg
9 from geometry_msgs.msg import Twist
10 from sensor_msgs.msg import LaserScan
11 from collections import deque
12 
13 
14 class xbot_scan180():
15  """
16  reduce rplidar scan from 360° to 180°
17  """
18 
19  def __init__(self):
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)
23  rate = rospy.Rate(20)
24  while not rospy.is_shutdown():
25  rate.sleep()
26 
27 
28  def scan_dataCB(self, scan_data):
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)
35 
36 
37 if __name__ == '__main__':
38  try:
39  rospy.loginfo("initialization system")
40  xbot_scan180()
41  rospy.loginfo("process done and quit")
42  except rospy.ROSInterruptException:
43  rospy.loginfo("xbot_scan180 terminated.")
44 
45 
def scan_dataCB(self, scan_data)
Definition: xbot_scan180.py:28


xbot_bringup
Author(s): Rocwang, Changkun
autogenerated on Sat Oct 10 2020 03:28:08