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 from geometry_msgs.msg import Twist
00015 import math
00016
00017
00018 class StateThread(threading.Thread):
00019 def __init__(self, axis):
00020 threading.Thread.__init__(self)
00021
00022 self.axis = axis
00023 self.daemon = True
00024
00025 def run(self):
00026 r = rospy.Rate(10)
00027 msg = Axis()
00028
00029 while True:
00030 if not self.axis.twist_timeout and ((rospy.Time.now() - self.axis.last_request).to_sec() > 1.0):
00031 self.axis.twist_timeout = True
00032 self.axis.cmd_twist(Twist(),reset_timeout=False)
00033 conn = httplib.HTTPConnection(self.axis.hostname)
00034 params = { 'query':'position' }
00035 conn.request("GET", "/axis-cgi/com/ptz.cgi?%s" % urllib.urlencode(params))
00036 response = conn.getresponse()
00037 if response.status == 200:
00038 body = response.read()
00039 params = dict([s.split('=',2) for s in body.splitlines()])
00040 msg.pan = float(params['pan'])
00041
00042 if self.axis.flip:
00043 msg.pan = 180 - msg.pan
00044 if msg.pan > 180:
00045 msg.pan -= 360
00046 if msg.pan < -180:
00047 msg.pan += 360
00048 msg.tilt = float(params['tilt'])
00049 msg.zoom = float(params['zoom'])
00050 msg.iris = float(params['iris'])
00051 msg.focus = 0.0
00052 if 'focus' in params:
00053 msg.focus = float(params['focus'])
00054 msg.autofocus = (params['autofocus'] == 'on')
00055 self.axis.pub.publish(msg)
00056 r.sleep()
00057
00058
00059 class AxisPTZ:
00060 def __init__(self, hostname, username, password, flip):
00061 self.hostname = hostname
00062 self.username = username
00063 self.password = password
00064 self.flip = flip
00065
00066 self.st = None
00067 self.twist_timeout = True
00068 self.pub = rospy.Publisher("state", Axis, self)
00069 self.sub = rospy.Subscriber("twist", Twist, self.cmd_twist)
00070 self.sub = rospy.Subscriber("cmd", Axis, self.cmd_abs)
00071 self.cmd_twist(Twist(),reset_timeout=False)
00072
00073 def peer_subscribe(self, topic_name, topic_publish, peer_publish):
00074
00075 if self.st is None:
00076 self.st = StateThread(self)
00077 self.st.start()
00078
00079 def cmd_abs(self, msg):
00080 if not self.twist_timeout:
00081 self.axis.twist_timeout = True
00082 self.axis.cmd_twist(Twist(),reset_timeout=False)
00083 conn = httplib.HTTPConnection(self.hostname)
00084
00085 if self.flip:
00086 msg.pan = 180 - msg.pan
00087 if msg.pan > 180:
00088 msg.pan -= 360
00089 if msg.pan < -180:
00090 msg.pan += 360
00091 params = { 'pan': msg.pan, 'tilt': msg.tilt, 'zoom': msg.zoom, 'brightness': msg.brightness }
00092 if msg.autofocus:
00093 params['autofocus'] = 'on'
00094 else:
00095 params['autofocus'] = 'off'
00096 params['focus'] = msg.focus
00097 if msg.iris > 0.000001:
00098 rospy.logwarn("Iris value is read-only.")
00099 conn.request("GET", "/axis-cgi/com/ptz.cgi?%s" % urllib.urlencode(params))
00100
00101 def cmd_twist(self, msg, reset_timeout=True):
00102 if reset_timeout:
00103 self.twist_timeout = False
00104 self.last_request = rospy.Time.now()
00105 conn = httplib.HTTPConnection(self.hostname)
00106 pan = int(msg.angular.z * 180./math.pi)
00107 tilt = int(msg.angular.y * 180./math.pi)
00108 if pan>100:
00109 pan=100
00110 if pan<-100:
00111 pan=-100
00112 if tilt>100:
00113 tilt=100
00114 if tilt<-100:
00115 tilt=-100
00116
00117 if self.flip:
00118 pan = -pan
00119 tilt = -tilt
00120 conn.request("GET", "/axis-cgi/com/ptz.cgi?continuouspantiltmove=%d,%d" % (pan,tilt))
00121
00122
00123 def main():
00124 rospy.init_node("axis_twist")
00125
00126 arg_defaults = {
00127 'hostname': '192.168.0.90',
00128 'username': '',
00129 'password': '',
00130 'flip': True,
00131 }
00132 args = {}
00133 for name in arg_defaults:
00134 args[name] = rospy.get_param(rospy.search_param(name), arg_defaults[name])
00135
00136 AxisPTZ(**args)
00137 rospy.spin()
00138
00139
00140 if __name__ == "__main__":
00141 main()