Go to the documentation of this file.00001
00002
00003 import roslib; roslib.load_manifest('panasonic_blc111')
00004 import rospy
00005 from panasonic_blc111.msg import *
00006 import urllib2
00007 import traceback,sys
00008
00009 cam_ip = '0.0.0.0'
00010 cam_user = 'aslteam'
00011 cam_pwd = '123456'
00012
00013
00014 class MyPwdManager(urllib2.HTTPPasswordMgrWithDefaultRealm):
00015 def find_user_password(self,realm,uri):
00016 return (cam_user,cam_pwd)
00017
00018
00019 auth_handler = urllib2.HTTPBasicAuthHandler(MyPwdManager())
00020 opener = urllib2.build_opener(auth_handler)
00021
00022 urllib2.install_opener(opener)
00023
00024 def ptcmdCallback(cmd):
00025 commands={ PTCmd.Home: 'HomePosition', PTCmd.PanLeft: 'PanLeft', \
00026 PTCmd.PanRight: 'PanRight', PTCmd.TiltUp: 'TiltUp', \
00027 PTCmd.TiltDown: 'TiltDown', PTCmd.PanScan: 'PanScan', \
00028 PTCmd.TiltScan: 'TiltScan'}
00029 url = 'http://'+cam_ip+'/nphControlCamera?Direction='+commands[cmd.command];
00030 try:
00031 print "Sending message to url: " + url
00032 f = urllib2.urlopen(url)
00033 dump = f.read()
00034 except:
00035 traceback.print_exc(file=sys.stderr)
00036
00037
00038 if __name__ == '__main__':
00039 home = PTCmd(command=PTCmd.Home)
00040 rospy.init_node('blc111_command')
00041 cam_ip = rospy.get_param("~cam_ip","0.0.0.0")
00042 listener = rospy.Subscriber("~command", PTCmd, ptcmdCallback)
00043
00044 ptcmdCallback(home)
00045 print "Subscribed to command topic. Ready to go"
00046 rospy.spin()
00047
00048