Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007 import os, sys, string, time, getopt, threading
00008 import httplib, urllib
00009
00010 import roslib; roslib.load_manifest('axis_camera')
00011 import rospy
00012
00013 from axis_camera.msg import Axis
00014
00015
00016 class StateThread(threading.Thread):
00017 def __init__(self, axis):
00018 threading.Thread.__init__(self)
00019
00020 self.axis = axis
00021 self.daemon = True
00022
00023 def run(self):
00024 r = rospy.Rate(10)
00025 msg = Axis()
00026
00027 while True:
00028 conn = httplib.HTTPConnection(self.axis.hostname)
00029 params = { 'query':'position' }
00030 conn.request("GET", "/axis-cgi/com/ptz.cgi?%s" % urllib.urlencode(params))
00031 response = conn.getresponse()
00032 if response.status == 200:
00033 body = response.read()
00034 params = dict([s.split('=',2) for s in body.splitlines()])
00035 msg.pan = float(params['pan'])
00036
00037 if self.axis.flip:
00038 msg.pan = 180 - msg.pan
00039 if msg.pan > 180:
00040 msg.pan -= 360
00041 if msg.pan < -180:
00042 msg.pan += 360
00043 msg.tilt = float(params['tilt'])
00044 msg.zoom = float(params['zoom'])
00045 msg.iris = float(params['iris'])
00046 msg.focus = 0.0
00047 if 'focus' in params:
00048 msg.focus = float(params['focus'])
00049 msg.autofocus = (params['autofocus'] == 'on')
00050 self.axis.pub.publish(msg)
00051 r.sleep()
00052
00053
00054 class AxisPTZ:
00055 def __init__(self, hostname, username, password, flip):
00056 self.hostname = hostname
00057 self.username = username
00058 self.password = password
00059 self.flip = flip
00060
00061 self.st = None
00062 self.pub = rospy.Publisher("state", Axis, self)
00063 self.sub = rospy.Subscriber("cmd", Axis, self.cmd)
00064
00065 def peer_subscribe(self, topic_name, topic_publish, peer_publish):
00066
00067 if self.st is None:
00068 self.st = StateThread(self)
00069 self.st.start()
00070
00071 def cmd(self, msg):
00072 conn = httplib.HTTPConnection(self.hostname)
00073
00074 if self.flip:
00075 msg.pan = 180 - msg.pan
00076 if msg.pan > 180:
00077 msg.pan -= 360
00078 if msg.pan < -180:
00079 msg.pan += 360
00080 params = { 'pan': msg.pan, 'tilt': msg.tilt, 'zoom': msg.zoom, 'brightness': msg.brightness }
00081 if msg.autofocus:
00082 params['autofocus'] = 'on'
00083 else:
00084 params['autofocus'] = 'off'
00085 params['focus'] = msg.focus
00086 if msg.iris > 0.000001:
00087 rospy.logwarn("Iris value is read-only.")
00088 conn.request("GET", "/axis-cgi/com/ptz.cgi?%s" % urllib.urlencode(params))
00089
00090
00091 def main():
00092 rospy.init_node("axis")
00093
00094 arg_defaults = {
00095 'hostname': '192.168.0.90',
00096 'username': '',
00097 'password': '',
00098 'flip': True,
00099 }
00100 args = {}
00101 for name in arg_defaults:
00102 args[name] = rospy.get_param(rospy.search_param(name), arg_defaults[name])
00103
00104 AxisPTZ(**args)
00105 rospy.spin()
00106
00107
00108 if __name__ == "__main__":
00109 main()