$search
00001 #!/usr/bin/env python 00002 00003 # SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/nao_robot/nao_driver/scripts/nao_tactile.py $ 00004 # SVN $Id: nao_tactile.py 2245 2011-11-28 16:25:56Z hornunga@informatik.uni-freiburg.de $ 00005 00006 00007 # 00008 # ROS node to read Nao's bumpers and tactile sensors 00009 # This code is currently compatible to NaoQI version 1.6 00010 # 00011 # Copyright 2010 Stefan Osswald, University of Freiburg 00012 # http://www.ros.org/wiki/nao 00013 # 00014 # Redistribution and use in source and binary forms, with or without 00015 # modification, are permitted provided that the following conditions are met: 00016 # 00017 # # Redistributions of source code must retain the above copyright 00018 # notice, this list of conditions and the following disclaimer. 00019 # # Redistributions in binary form must reproduce the above copyright 00020 # notice, this list of conditions and the following disclaimer in the 00021 # documentation and/or other materials provided with the distribution. 00022 # # Neither the name of the University of Freiburg nor the names of its 00023 # contributors may be used to endorse or promote products derived from 00024 # this software without specific prior written permission. 00025 # 00026 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00027 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00028 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00029 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00030 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00031 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00032 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00033 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00034 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00035 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00036 # POSSIBILITY OF SUCH DAMAGE. 00037 # 00038 00039 00040 import roslib 00041 roslib.load_manifest('nao_driver') 00042 import rospy 00043 00044 from naoqi import * 00045 from nao_msgs.msg import TactileTouch, Bumper 00046 from std_msgs.msg import Bool 00047 from nao_driver import * 00048 00049 # 00050 # Notes: 00051 # - A port number > 0 for the module must be specified. 00052 # If port 0 is used, a free port will be assigned automatically, 00053 # but naoqi is unable to pick up the assigned port number, leaving 00054 # the module unable to communicate with naoqi (1.10.52). 00055 # 00056 # - Callback functions _must_ have a docstring, otherwise they won't get bound. 00057 # 00058 # - Shutting down the broker manually will result in a deadlock, 00059 # not shutting down the broker will sometimes result in an exception 00060 # when the script ends (1.10.52). 00061 # 00062 00063 class NaoTactile(ALModule): 00064 "Sends callbacks for tactile touch, bumper press and foot contact to ROS" 00065 def __init__(self, moduleName): 00066 # get connection from command line: 00067 from optparse import OptionParser 00068 00069 parser = OptionParser() 00070 parser.add_option("--ip", dest="ip", default="", 00071 help="IP/hostname of broker. Default is system's default IP address.", metavar="IP") 00072 parser.add_option("--port", dest="port", default=10511, 00073 help="IP/hostname of broker. Default is 10511.", metavar="PORT") 00074 parser.add_option("--pip", dest="pip", default="127.0.0.1", 00075 help="IP/hostname of parent broker. Default is 127.0.0.1.", metavar="IP") 00076 parser.add_option("--pport", dest="pport", default=9559, 00077 help="port of parent broker. Default is 9559.", metavar="PORT") 00078 00079 (options, args) = parser.parse_args() 00080 self.ip = options.ip 00081 self.port = int(options.port) 00082 self.pip = options.pip 00083 self.pport = int(options.pport) 00084 self.moduleName = moduleName 00085 00086 self.init_almodule() 00087 00088 # ROS initialization: 00089 rospy.init_node('nao_tactile') 00090 00091 # init. messages: 00092 self.tactile = TactileTouch() 00093 self.bumper = Bumper() 00094 self.tactilePub = rospy.Publisher("tactile_touch", TactileTouch) 00095 self.bumperPub = rospy.Publisher("bumper", Bumper) 00096 00097 try: 00098 footContact = self.memProxy.getData("footContact", 0) 00099 except RuntimeError: 00100 footContact = None 00101 00102 if footContact is None: 00103 self.hasFootContactKey = False 00104 rospy.loginfo("Foot contact key is not present in ALMemory, will not publish to foot_contact topic.") 00105 else: 00106 self.hasFootContactKey = True 00107 self.footContactPub = rospy.Publisher("foot_contact", Bool, latch=True) 00108 self.footContactPub.publish(footContact > 0.0) 00109 00110 # constants in TactileTouch and Bumper will not be available in callback functions 00111 # as they are executed in the parent broker context (i.e. on robot), 00112 # so they have to be copied to member variables 00113 self.tactileTouchFrontButton = TactileTouch.buttonFront; 00114 self.tactileTouchMiddleButton = TactileTouch.buttonMiddle; 00115 self.tactileTouchRearButton = TactileTouch.buttonRear; 00116 self.bumperRightButton = Bumper.right; 00117 self.bumperLeftButton = Bumper.left; 00118 00119 self.subscribe() 00120 00121 rospy.loginfo("nao_tactile initialized") 00122 00123 def init_almodule(self): 00124 # before we can instantiate an ALModule, an ALBroker has to be created 00125 rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport) 00126 try: 00127 self.broker = ALBroker("%sBroker" % self.moduleName, self.ip, self.port, self.pip, self.pport) 00128 except RuntimeError,e: 00129 print("Could not connect to NaoQi's main broker") 00130 exit(1) 00131 ALModule.__init__(self, self.moduleName) 00132 00133 self.memProxy = ALProxy("ALMemory",self.pip,self.pport) 00134 # TODO: check self.memProxy.version() for > 1.6 00135 if self.memProxy is None: 00136 rospy.logerror("Could not get a proxy to ALMemory on %s:%d", self.pip, self.pport) 00137 exit(1) 00138 00139 00140 def shutdown(self): 00141 self.unsubscribe() 00142 # Shutting down broker seems to be not necessary any more 00143 # try: 00144 # self.broker.shutdown() 00145 # except RuntimeError,e: 00146 # rospy.logwarn("Could not shut down Python Broker: %s", e) 00147 00148 00149 def subscribe(self): 00150 self.memProxy.subscribeToEvent("FrontTactilTouched", self.moduleName, "onTactileChanged") 00151 self.memProxy.subscribeToEvent("MiddleTactilTouched", self.moduleName, "onTactileChanged") 00152 self.memProxy.subscribeToEvent("RearTactilTouched", self.moduleName, "onTactileChanged") 00153 self.memProxy.subscribeToEvent("RightBumperPressed", self.moduleName, "onBumperChanged") 00154 self.memProxy.subscribeToEvent("LeftBumperPressed", self.moduleName, "onBumperChanged") 00155 if self.hasFootContactKey: 00156 self.memProxy.subscribeToEvent("footContactChanged", self.moduleName, "onFootContactChanged") 00157 00158 00159 def unsubscribe(self): 00160 self.memProxy.unsubscribeToEvent("FrontTactilTouched", self.moduleName) 00161 self.memProxy.unsubscribeToEvent("MiddleTactilTouched", self.moduleName) 00162 self.memProxy.unsubscribeToEvent("RearTactilTouched", self.moduleName) 00163 self.memProxy.unsubscribeToEvent("RightBumperPressed", self.moduleName) 00164 self.memProxy.unsubscribeToEvent("LeftBumperPressed", self.moduleName) 00165 if self.hasFootContactKey: 00166 self.memProxy.unsubscribeToEvent("footContactChanged", self.moduleName) 00167 00168 00169 def onTactileChanged(self, strVarName, value, strMessage): 00170 "Called when tactile touch status changes in ALMemory" 00171 if strVarName == "FrontTactilTouched": 00172 self.tactile.button = self.tactileTouchFrontButton 00173 elif strVarName == "MiddleTactilTouched": 00174 self.tactile.button = self.tactileTouchMiddleButton 00175 elif strVarName == "RearTactilTouched": 00176 self.tactile.button = self.tactileTouchRearButton 00177 00178 self.tactile.state = int(value); 00179 self.tactilePub.publish(self.tactile) 00180 rospy.logdebug("tactile touched: name=%s, value=%d, message=%s.", strVarName, value, strMessage); 00181 00182 def onBumperChanged(self, strVarName, value, strMessage): 00183 "Called when bumper status changes in ALMemory" 00184 if strVarName == "RightBumperPressed": 00185 self.bumper.bumper = self.bumperRightButton 00186 elif strVarName == "LeftBumperPressed": 00187 self.bumper.bumper = self.bumperLeftButton 00188 00189 self.bumper.state = int(value); 00190 self.bumperPub.publish(self.bumper) 00191 rospy.logdebug("bumper pressed: name=%s, value=%d, message=%s.", strVarName, value, strMessage); 00192 00193 def onFootContactChanged(self, strVarName, value, strMessage): 00194 "Called when foot contact changes in ALMemory" 00195 self.footContactPub.publish(value > 0.0) 00196 00197 if __name__ == '__main__': 00198 ROSNaoTactileModule = NaoTactile("ROSNaoTactileModule") 00199 00200 rospy.spin() 00201 00202 rospy.loginfo("Stopping nao_tactile ...") 00203 ROSNaoTactileModule.shutdown(); 00204 rospy.loginfo("nao_tactile stopped.") 00205 exit(0)