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