Go to the documentation of this file.00001
00002
00003 """
00004 max_sonar.py - convert analog stream into range measurements
00005 Copyright (c) 2011 Vanadium Labs LLC. All right reserved.
00006
00007 Redistribution and use in source and binary forms, with or without
00008 modification, are permitted provided that the following conditions are met:
00009 * Redistributions of source code must retain the above copyright
00010 notice, this list of conditions and the following disclaimer.
00011 * Redistributions in binary form must reproduce the above copyright
00012 notice, this list of conditions and the following disclaimer in the
00013 documentation and/or other materials provided with the distribution.
00014 * Neither the name of Vanadium Labs LLC nor the names of its
00015 contributors may be used to endorse or promote products derived
00016 from this software without specific prior written permission.
00017
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00019 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT,
00022 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00023 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00024 OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00025 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00026 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00027 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 """
00029
00030 import roslib; roslib.load_manifest('arbotix_sensors')
00031 import rospy
00032
00033 from sensor_msgs.msg import Range
00034 from arbotix_msgs.msg import Analog
00035 from arbotix_msgs.srv import SetupChannel, SetupChannelRequest
00036
00037 from arbotix_python.sensors import *
00038
00039 class max_sonar:
00040 def __init__(self):
00041 rospy.init_node("max_sonar")
00042
00043 self.sensor = maxSonar()
00044
00045
00046 rospy.wait_for_service('arbotix/SetupAnalogIn')
00047 analog_srv = rospy.ServiceProxy('arbotix/SetupAnalogIn', SetupChannel)
00048
00049 req = SetupChannelRequest()
00050 req.topic_name = rospy.get_param("~name")
00051 req.pin = rospy.get_param("~pin")
00052 req.rate = int(rospy.get_param("~rate",10))
00053 analog_srv(req)
00054
00055
00056 self.msg = Range()
00057 self.msg.radiation_type = self.sensor.radiation_type
00058 self.msg.field_of_view = self.sensor.field_of_view
00059 self.msg.min_range = self.sensor.min_range
00060 self.msg.max_range = self.sensor.max_range
00061
00062
00063 self.pub = rospy.Publisher("sonar_range", Range)
00064 rospy.Subscriber("arbotix/"+req.topic_name, Analog, self.readingCb)
00065
00066 rospy.spin()
00067
00068 def readingCb(self, msg):
00069
00070 self.msg.header.stamp = rospy.Time.now()
00071 self.msg.range = self.sensor.convert(msg.value<<2)
00072 self.pub.publish(self.msg)
00073
00074 if __name__=="__main__":
00075 max_sonar()
00076