io.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 """
4  io.py - ROS wrappers for ArbotiX I/O
5  Copyright (c) 2010-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 from arbotix_msgs.msg import *
32 
34  """ Class for a digital output. """
35  def __init__(self, name, pin, value, rate, device):
36  self.device = device
37  self.value = value
38  self.direction = 0
39  self.pin = pin
40  self.device.setDigital(self.pin, self.value, self.direction)
41  rospy.Subscriber('~'+name, Digital, self.stateCb)
42  self.t_delta = rospy.Duration(1.0/rate)
43  self.t_next = rospy.Time.now() + self.t_delta
44  def stateCb(self, msg):
45  self.value = msg.value
46  self.direction = msg.direction
47  def update(self):
48  if rospy.Time.now() > self.t_next:
49  self.device.setDigital(self.pin, self.value, self.direction)
50  self.t_next = rospy.Time.now() + self.t_delta
51 
53  """ Class for a digital input. """
54  def __init__(self, name, pin, value, rate, device):
55  self.device = device
56  self.pin = pin
57  self.device.setDigital(pin, value, 0)
58  self.pub = rospy.Publisher('~'+name, Digital, queue_size=5)
59  self.t_delta = rospy.Duration(1.0/rate)
60  self.t_next = rospy.Time.now() + self.t_delta
61  def update(self):
62  if rospy.Time.now() > self.t_next:
63  msg = Digital()
64  msg.header.stamp = rospy.Time.now()
65  msg.value = self.device.getDigital(self.pin)
66  self.pub.publish(msg)
67  self.t_next = rospy.Time.now() + self.t_delta
68 
70  """ Class for an analog input. """
71  def __init__(self, name, pin, value, rate, leng, device):
72  self.device = device
73  self.pin = pin
74  self.device.setDigital(pin, value, 0)
75  self.pub = rospy.Publisher('~'+name, Analog, queue_size=5)
76  self.t_delta = rospy.Duration(1.0/rate)
77  self.t_next = rospy.Time.now() + self.t_delta
78  self.leng = leng
79  def update(self):
80  if rospy.Time.now() > self.t_next:
81  msg = Analog()
82  msg.header.stamp = rospy.Time.now()
83  msg.value = self.device.getAnalog(self.pin, self.leng)
84  if msg.value >= 0:
85  self.pub.publish(msg)
86  self.t_next = rospy.Time.now() + self.t_delta
87 
def __init__(self, name, pin, value, rate, leng, device)
Definition: io.py:71
def stateCb(self, msg)
Definition: io.py:44
def __init__(self, name, pin, value, rate, device)
Definition: io.py:54
def __init__(self, name, pin, value, rate, device)
Definition: io.py:35


arbotix_python
Author(s): Michael Ferguson
autogenerated on Mon Jun 10 2019 12:43:36