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 rospy
00031
00032 from sensor_msgs.msg import Range
00033 from arbotix_msgs.msg import Analog
00034 from arbotix_msgs.srv import SetupChannel, SetupChannelRequest
00035
00036 from arbotix_python.sensors import *
00037
00038 class max_sonar:
00039 def __init__(self):
00040 rospy.init_node("max_sonar")
00041
00042 self.sensor = maxSonar()
00043
00044
00045 rospy.wait_for_service('arbotix/SetupAnalogIn')
00046 analog_srv = rospy.ServiceProxy('arbotix/SetupAnalogIn', SetupChannel)
00047
00048 req = SetupChannelRequest()
00049 req.topic_name = rospy.get_param("~name")
00050 req.pin = rospy.get_param("~pin")
00051 req.rate = int(rospy.get_param("~rate",10))
00052 analog_srv(req)
00053
00054
00055 self.msg = Range()
00056 self.msg.radiation_type = self.sensor.radiation_type
00057 self.msg.field_of_view = self.sensor.field_of_view
00058 self.msg.min_range = self.sensor.min_range
00059 self.msg.max_range = self.sensor.max_range
00060
00061
00062 self.pub = rospy.Publisher("sonar_range", Range, queue_size=5)
00063 rospy.Subscriber("arbotix/"+req.topic_name, Analog, self.readingCb)
00064
00065 rospy.spin()
00066
00067 def readingCb(self, msg):
00068
00069 self.msg.header.stamp = rospy.Time.now()
00070 self.msg.range = self.sensor.convert(msg.value<<2)
00071 self.pub.publish(self.msg)
00072
00073 if __name__=="__main__":
00074 max_sonar()
00075