00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 import roslib
00037 roslib.load_manifest('nao_driver')
00038 import rospy
00039
00040 from naoqi import *
00041 from nao_msgs.msg import TactileTouch, Bumper
00042 from std_msgs.msg import Bool
00043 from nao_driver import *
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059 class NaoTactile(ALModule):
00060 "Sends callbacks for tactile touch, bumper press and foot contact to ROS"
00061 def __init__(self, moduleName):
00062
00063 from optparse import OptionParser
00064
00065 parser = OptionParser()
00066 parser.add_option("--ip", dest="ip", default="",
00067 help="IP/hostname of broker. Default is system's default IP address.", metavar="IP")
00068 parser.add_option("--port", dest="port", default=10511,
00069 help="IP/hostname of broker. Default is 10511.", metavar="PORT")
00070 parser.add_option("--pip", dest="pip", default="127.0.0.1",
00071 help="IP/hostname of parent broker. Default is 127.0.0.1.", metavar="IP")
00072 parser.add_option("--pport", dest="pport", default=9559,
00073 help="port of parent broker. Default is 9559.", metavar="PORT")
00074
00075 (options, args) = parser.parse_args()
00076 self.ip = options.ip
00077 self.port = int(options.port)
00078 self.pip = options.pip
00079 self.pport = int(options.pport)
00080 self.moduleName = moduleName
00081
00082 self.init_almodule()
00083
00084
00085 rospy.init_node('nao_tactile')
00086
00087
00088 self.tactile = TactileTouch()
00089 self.bumper = Bumper()
00090 self.tactilePub = rospy.Publisher("tactile_touch", TactileTouch)
00091 self.bumperPub = rospy.Publisher("bumper", Bumper)
00092
00093 try:
00094 footContact = self.memProxy.getData("footContact", 0)
00095 except RuntimeError:
00096 footContact = None
00097
00098 if footContact is None:
00099 self.hasFootContactKey = False
00100 rospy.loginfo("Foot contact key is not present in ALMemory, will not publish to foot_contact topic.")
00101 else:
00102 self.hasFootContactKey = True
00103 self.footContactPub = rospy.Publisher("foot_contact", Bool, latch=True)
00104 self.footContactPub.publish(footContact > 0.0)
00105
00106
00107
00108
00109 self.tactileTouchFrontButton = TactileTouch.buttonFront;
00110 self.tactileTouchMiddleButton = TactileTouch.buttonMiddle;
00111 self.tactileTouchRearButton = TactileTouch.buttonRear;
00112 self.bumperRightButton = Bumper.right;
00113 self.bumperLeftButton = Bumper.left;
00114
00115 self.subscribe()
00116
00117 rospy.loginfo("nao_tactile initialized")
00118
00119 def init_almodule(self):
00120
00121 rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
00122 try:
00123 self.broker = ALBroker("%sBroker" % self.moduleName, self.ip, self.port, self.pip, self.pport)
00124 except RuntimeError,e:
00125 print("Could not connect to NaoQi's main broker")
00126 exit(1)
00127 ALModule.__init__(self, self.moduleName)
00128
00129 self.memProxy = ALProxy("ALMemory",self.pip,self.pport)
00130
00131 if self.memProxy is None:
00132 rospy.logerror("Could not get a proxy to ALMemory on %s:%d", self.pip, self.pport)
00133 exit(1)
00134
00135
00136 def shutdown(self):
00137 self.unsubscribe()
00138
00139
00140
00141
00142
00143
00144
00145 def subscribe(self):
00146 self.memProxy.subscribeToEvent("FrontTactilTouched", self.moduleName, "onTactileChanged")
00147 self.memProxy.subscribeToEvent("MiddleTactilTouched", self.moduleName, "onTactileChanged")
00148 self.memProxy.subscribeToEvent("RearTactilTouched", self.moduleName, "onTactileChanged")
00149 self.memProxy.subscribeToEvent("RightBumperPressed", self.moduleName, "onBumperChanged")
00150 self.memProxy.subscribeToEvent("LeftBumperPressed", self.moduleName, "onBumperChanged")
00151 if self.hasFootContactKey:
00152 self.memProxy.subscribeToEvent("footContactChanged", self.moduleName, "onFootContactChanged")
00153
00154
00155 def unsubscribe(self):
00156 self.memProxy.unsubscribeToEvent("FrontTactilTouched", self.moduleName)
00157 self.memProxy.unsubscribeToEvent("MiddleTactilTouched", self.moduleName)
00158 self.memProxy.unsubscribeToEvent("RearTactilTouched", self.moduleName)
00159 self.memProxy.unsubscribeToEvent("RightBumperPressed", self.moduleName)
00160 self.memProxy.unsubscribeToEvent("LeftBumperPressed", self.moduleName)
00161 if self.hasFootContactKey:
00162 self.memProxy.unsubscribeToEvent("footContactChanged", self.moduleName)
00163
00164
00165 def onTactileChanged(self, strVarName, value, strMessage):
00166 "Called when tactile touch status changes in ALMemory"
00167 if strVarName == "FrontTactilTouched":
00168 self.tactile.button = self.tactileTouchFrontButton
00169 elif strVarName == "MiddleTactilTouched":
00170 self.tactile.button = self.tactileTouchMiddleButton
00171 elif strVarName == "RearTactilTouched":
00172 self.tactile.button = self.tactileTouchRearButton
00173
00174 self.tactile.state = int(value);
00175 self.tactilePub.publish(self.tactile)
00176 rospy.logdebug("tactile touched: name=%s, value=%d, message=%s.", strVarName, value, strMessage);
00177
00178 def onBumperChanged(self, strVarName, value, strMessage):
00179 "Called when bumper status changes in ALMemory"
00180 if strVarName == "RightBumperPressed":
00181 self.bumper.bumper = self.bumperRightButton
00182 elif strVarName == "LeftBumperPressed":
00183 self.bumper.bumper = self.bumperLeftButton
00184
00185 self.bumper.state = int(value);
00186 self.bumperPub.publish(self.bumper)
00187 rospy.logdebug("bumper pressed: name=%s, value=%d, message=%s.", strVarName, value, strMessage);
00188
00189 def onFootContactChanged(self, strVarName, value, strMessage):
00190 "Called when foot contact changes in ALMemory"
00191 self.footContactPub.publish(value > 0.0)
00192
00193 if __name__ == '__main__':
00194 ROSNaoTactileModule = NaoTactile("ROSNaoTactileModule")
00195
00196 rospy.spin()
00197
00198 rospy.loginfo("Stopping nao_tactile ...")
00199 ROSNaoTactileModule.shutdown();
00200 rospy.loginfo("nao_tactile stopped.")
00201 exit(0)