rep117_filter.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 from sensor_msgs.msg import LaserScan
5 
6 pub = None
7 
8 def callback(msg):
9  """
10  Convert laser scans to REP 117 standard:
11  http://www.ros.org/reps/rep-0117.html
12  """
13  ranges_out = []
14  for dist in msg.ranges:
15  if dist < msg.range_min:
16  # assume "reading too close to measure",
17  # although it could also be "reading invalid" (nan)
18  ranges_out.append(float("-inf"))
19 
20  elif dist > msg.range_max:
21  # assume "reading of no return (outside sensor range)",
22  # although it could also be "reading invalid" (nan)
23  ranges_out.append(float("inf"))
24  else:
25  ranges_out.append(dist)
26 
27  msg.ranges = ranges_out
28  pub.publish(msg)
29 
30 def main():
31  global pub
32  rospy.init_node('rep117_filter')
33 
34  pub = rospy.Publisher('scan_filtered', LaserScan, queue_size=10)
35  rospy.Subscriber('scan', LaserScan, callback)
36  rospy.spin()
37 
38 if __name__ == '__main__':
39  try:
40  main()
41  except rospy.ROSInterruptException:
42  pass
def callback(msg)
Definition: rep117_filter.py:8


mir_driver
Author(s): Martin Günther
autogenerated on Wed May 8 2019 02:38:53