Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 """
00035 This module handles sonar messages from the Arduino Mega 2560 mounted
00036 on BWI segbots, publishing them as ROS sensor_msgs/Range.
00037 """
00038
00039
00040 from __future__ import absolute_import, print_function, unicode_literals
00041
00042 import re
00043
00044 import rospy
00045 from sensor_msgs.msg import Range
00046
00047
00048 class SonarAttributes(Range):
00049 """ Subclass of sensor_msgs/Range, for filling in sonar attributes."""
00050 def __init__(self, frame_id,
00051 field_of_view=0.5, min_range=0.01, max_range=2.0):
00052 super(SonarAttributes, self).__init__(
00053 radiation_type=Range.ULTRASOUND,
00054 field_of_view=field_of_view,
00055 min_range=min_range,
00056 max_range=max_range)
00057 if frame_id:
00058 self.header.frame_id = frame_id
00059
00060
00061 class SonarMessages(object):
00062 """ ROS message translation for UTexas BWI segbot Arduino sonar ranges. """
00063 def __init__(self):
00064 self.pub = rospy.Publisher('sonar', Range)
00065 self.parser = re.compile(r'(\d+)=(\d+)cm')
00066 """ Extracts list of distances from the Arduino serial message.
00067
00068 :returns: List of (sonar, distance) pairs of strings reported
00069 for the sonars, may be empty.
00070 """
00071
00072
00073
00074 self.sonars = [
00075 SonarAttributes('sonar0'),
00076 SonarAttributes('sonar1'),
00077 SonarAttributes('sonar2')]
00078
00079 def publish(self, serial_msg):
00080 """ Publish a ROS Range message for each reading.
00081
00082 :param serial_msg: sonar message from Arduino.
00083 :type serial_msg: str
00084 """
00085
00086
00087
00088 readings = self.parser.findall(serial_msg)
00089 if not readings:
00090 return
00091 now = rospy.Time.now()
00092 for sonar, distance in readings:
00093 sonar = int(sonar)
00094 if sonar >= len(self.sonars):
00095 continue
00096 msg = self.sonars[sonar]
00097 msg.header.stamp = now
00098 distance = int(distance)
00099 if distance == 0:
00100 msg.range = float('+inf')
00101 else:
00102
00103 msg.range = 0.01 * float(distance)
00104 self.pub.publish(msg)
00105
00106
00107 sonar = SonarMessages()
00108 handler = sonar.publish
00109 """ This interface is called once for each sonar message received. """