max_sonar.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 """
4  max_sonar.py - convert analog stream into range measurements
5  Copyright (c) 2011 Vanadium Labs LLC. All right reserved.
6 
7  Redistribution and use in source and binary forms, with or without
8  modification, are permitted provided that the following conditions are met:
9  * Redistributions of source code must retain the above copyright
10  notice, this list of conditions and the following disclaimer.
11  * Redistributions in binary form must reproduce the above copyright
12  notice, this list of conditions and the following disclaimer in the
13  documentation and/or other materials provided with the distribution.
14  * Neither the name of Vanadium Labs LLC nor the names of its
15  contributors may be used to endorse or promote products derived
16  from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
19  ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
20  WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21  DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT,
22  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
23  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
24  OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
25  LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
26  OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
27  ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 """
29 
30 import rospy
31 
32 from sensor_msgs.msg import Range
33 from arbotix_msgs.msg import Analog
34 from arbotix_msgs.srv import SetupChannel, SetupChannelRequest
35 
36 from arbotix_python.sensors import *
37 
38 class max_sonar:
39  def __init__(self):
40  rospy.init_node("max_sonar")
41 
42  self.sensor = maxSonar()
43 
44  # start channel broadcast using SetupAnalogIn
45  rospy.wait_for_service('arbotix/SetupAnalogIn')
46  analog_srv = rospy.ServiceProxy('arbotix/SetupAnalogIn', SetupChannel)
47 
48  req = SetupChannelRequest()
49  req.topic_name = rospy.get_param("~name")
50  req.pin = rospy.get_param("~pin")
51  req.rate = int(rospy.get_param("~rate",10))
52  analog_srv(req)
53 
54  # setup a range message to use
55  self.msg = Range()
56  self.msg.radiation_type = self.sensor.radiation_type
57  self.msg.field_of_view = self.sensor.field_of_view
58  self.msg.min_range = self.sensor.min_range
59  self.msg.max_range = self.sensor.max_range
60 
61  # publish/subscribe
62  self.pub = rospy.Publisher("sonar_range", Range, queue_size=5)
63  rospy.Subscriber("arbotix/"+req.topic_name, Analog, self.readingCb)
64 
65  rospy.spin()
66 
67  def readingCb(self, msg):
68  # convert msg.value into range.range
69  self.msg.header.stamp = rospy.Time.now()
70  self.msg.range = self.sensor.convert(msg.value<<2)
71  self.pub.publish(self.msg)
72 
73 if __name__=="__main__":
74  max_sonar()
75 
def __init__(self)
Definition: max_sonar.py:39
def readingCb(self, msg)
Definition: max_sonar.py:67


arbotix_sensors
Author(s): Michael Ferguson
autogenerated on Fri Jun 7 2019 21:54:15