contact.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 #
4 # ROS node to read Nao's bumpers and tactile sensors
5 # This code is currently compatible to NaoQI version 1.6
6 #
7 # Copyright 2010 Stefan Osswald, University of Freiburg
8 # http://www.ros.org/wiki/nao
9 #
10 # Redistribution and use in source and binary forms, with or without
11 # modification, are permitted provided that the following conditions are met:
12 #
13 # # Redistributions of source code must retain the above copyright
14 # notice, this list of conditions and the following disclaimer.
15 # # Redistributions in binary form must reproduce the above copyright
16 # notice, this list of conditions and the following disclaimer in the
17 # documentation and/or other materials provided with the distribution.
18 # # Neither the name of the University of Freiburg nor the names of its
19 # contributors may be used to endorse or promote products derived from
20 # this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
23 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
24 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
25 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
26 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
27 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
28 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
29 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
30 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
31 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 #
34 
35 import rospy
36 
37 import naoqi
38 from naoqi_bridge_msgs.msg import TactileTouch, Bumper
39 from std_msgs.msg import Bool
40 from naoqi_driver.naoqi_node import NaoqiNode
41 from naoqi import ( ALModule, ALBroker, ALProxy )
42 
43 #
44 # Notes:
45 # - A port number > 0 for the module must be specified.
46 # If port 0 is used, a free port will be assigned automatically,
47 # but naoqi is unable to pick up the assigned port number, leaving
48 # the module unable to communicate with naoqi (1.10.52).
49 #
50 # - Callback functions _must_ have a docstring, otherwise they won't get bound.
51 #
52 # - Shutting down the broker manually will result in a deadlock,
53 # not shutting down the broker will sometimes result in an exception
54 # when the script ends (1.10.52).
55 #
56 
57 class NaoqiTactile(ALModule):
58  "Sends callbacks for tactile touch, bumper press and foot contact to ROS"
59  def __init__(self, moduleName):
60  # get connection from command line:
61  from optparse import OptionParser
62 
63  parser = OptionParser()
64  parser.add_option("--ip", dest="ip", default="",
65  help="IP/hostname of broker. Default is system's default IP address.", metavar="IP")
66  parser.add_option("--port", dest="port", default=0,
67  help="IP/hostname of broker. Default is automatic port.", metavar="PORT")
68  parser.add_option("--pip", dest="pip", default="127.0.0.1",
69  help="IP/hostname of parent broker. Default is 127.0.0.1.", metavar="IP")
70  parser.add_option("--pport", dest="pport", default=9559,
71  help="port of parent broker. Default is 9559.", metavar="PORT")
72 
73  (options, args) = parser.parse_args()
74  self.ip = options.ip
75  self.port = int(options.port)
76  self.pip = options.pip
77  self.pport = int(options.pport)
78  self.moduleName = moduleName
79 
80  self.init_almodule()
81 
82  # ROS initialization:
83  rospy.init_node('naoqi_tactile')
84 
85  # init. messages:
86  self.tactile = TactileTouch()
87  self.bumper = Bumper()
88  self.tactilePub = rospy.Publisher("tactile_touch", TactileTouch, queue_size=1)
89  self.bumperPub = rospy.Publisher("bumper", Bumper, queue_size=1)
90 
91  try:
92  footContact = self.memProxy.getData("footContact", 0)
93  except RuntimeError:
94  footContact = None
95 
96  if footContact is None:
97  self.hasFootContactKey = False
98  rospy.loginfo("Foot contact key is not present in ALMemory, will not publish to foot_contact topic.")
99  else:
100  self.hasFootContactKey = True
101  self.footContactPub = rospy.Publisher("foot_contact", Bool, latch=True, queue_size=1)
102  self.footContactPub.publish(footContact > 0.0)
103 
104  # constants in TactileTouch and Bumper will not be available in callback functions
105  # as they are executed in the parent broker context (i.e. on robot),
106  # so they have to be copied to member variables
107  self.tactileTouchFrontButton = TactileTouch.buttonFront;
108  self.tactileTouchMiddleButton = TactileTouch.buttonMiddle;
109  self.tactileTouchRearButton = TactileTouch.buttonRear;
110  self.bumperRightButton = Bumper.right;
111  self.bumperLeftButton = Bumper.left;
112 
113  self.subscribe()
114 
115  rospy.loginfo("nao_tactile initialized")
116 
117  def init_almodule(self):
118  # before we can instantiate an ALModule, an ALBroker has to be created
119  rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
120  try:
121  self.broker = ALBroker("%sBroker" % self.moduleName, self.ip, self.port, self.pip, self.pport)
122  except RuntimeError,e:
123  print("Could not connect to NaoQi's main broker")
124  exit(1)
125  ALModule.__init__(self, self.moduleName)
126 
127  self.memProxy = ALProxy("ALMemory",self.pip,self.pport)
128  # TODO: check self.memProxy.version() for > 1.6
129  if self.memProxy is None:
130  rospy.logerror("Could not get a proxy to ALMemory on %s:%d", self.pip, self.pport)
131  exit(1)
132 
133 
134  def shutdown(self):
135  self.unsubscribe()
136  # Shutting down broker seems to be not necessary any more
137  # try:
138  # self.broker.shutdown()
139  # except RuntimeError,e:
140  # rospy.logwarn("Could not shut down Python Broker: %s", e)
141 
142 
143  def subscribe(self):
144  self.memProxy.subscribeToEvent("FrontTactilTouched", self.moduleName, "onTactileChanged")
145  self.memProxy.subscribeToEvent("MiddleTactilTouched", self.moduleName, "onTactileChanged")
146  self.memProxy.subscribeToEvent("RearTactilTouched", self.moduleName, "onTactileChanged")
147  self.memProxy.subscribeToEvent("RightBumperPressed", self.moduleName, "onBumperChanged")
148  self.memProxy.subscribeToEvent("LeftBumperPressed", self.moduleName, "onBumperChanged")
149  if self.hasFootContactKey:
150  self.memProxy.subscribeToEvent("footContactChanged", self.moduleName, "onFootContactChanged")
151 
152 
153  def unsubscribe(self):
154  self.memProxy.unsubscribeToEvent("FrontTactilTouched", self.moduleName)
155  self.memProxy.unsubscribeToEvent("MiddleTactilTouched", self.moduleName)
156  self.memProxy.unsubscribeToEvent("RearTactilTouched", self.moduleName)
157  self.memProxy.unsubscribeToEvent("RightBumperPressed", self.moduleName)
158  self.memProxy.unsubscribeToEvent("LeftBumperPressed", self.moduleName)
159  if self.hasFootContactKey:
160  self.memProxy.unsubscribeToEvent("footContactChanged", self.moduleName)
161 
162 
163  def onTactileChanged(self, strVarName, value, strMessage):
164  "Called when tactile touch status changes in ALMemory"
165  if strVarName == "FrontTactilTouched":
166  self.tactile.button = self.tactileTouchFrontButton
167  elif strVarName == "MiddleTactilTouched":
168  self.tactile.button = self.tactileTouchMiddleButton
169  elif strVarName == "RearTactilTouched":
170  self.tactile.button = self.tactileTouchRearButton
171 
172  self.tactile.state = int(value);
173  self.tactilePub.publish(self.tactile)
174  rospy.logdebug("tactile touched: name=%s, value=%d, message=%s.", strVarName, value, strMessage);
175 
176  def onBumperChanged(self, strVarName, value, strMessage):
177  "Called when bumper status changes in ALMemory"
178  if strVarName == "RightBumperPressed":
179  self.bumper.bumper = self.bumperRightButton
180  elif strVarName == "LeftBumperPressed":
181  self.bumper.bumper = self.bumperLeftButton
182 
183  self.bumper.state = int(value);
184  self.bumperPub.publish(self.bumper)
185  rospy.logdebug("bumper pressed: name=%s, value=%d, message=%s.", strVarName, value, strMessage);
186 
187  def onFootContactChanged(self, strVarName, value, strMessage):
188  "Called when foot contact changes in ALMemory"
189  self.footContactPub.publish(value > 0.0)
190 
191 if __name__ == '__main__':
192  ROSNaoTactileModule = NaoqiTactile("ROSNaoTactileModule")
193 
194  rospy.spin()
195 
196  rospy.loginfo("Stopping nao_tactile ...")
197  ROSNaoTactileModule.shutdown();
198  rospy.loginfo("nao_tactile stopped.")
199  exit(0)
def onTactileChanged(self, strVarName, value, strMessage)
Definition: contact.py:163
def onBumperChanged(self, strVarName, value, strMessage)
Definition: contact.py:176
def subscribe(self)
Definition: contact.py:143
def init_almodule(self)
Definition: contact.py:117
def onFootContactChanged(self, strVarName, value, strMessage)
Definition: contact.py:187
def shutdown(self)
Definition: contact.py:134
def unsubscribe(self)
Definition: contact.py:153
def __init__(self, moduleName)
Definition: contact.py:59


naoqi_sensors_py
Author(s): Séverin Lemaignan, Vincent Rabaud, Karsten Knese, Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy, Daniel Maier
autogenerated on Thu Jul 16 2020 03:18:33