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
00037 import socket
00038 import subprocess
00039
00040 import roslib
00041 roslib.load_manifest('roswww')
00042 import rospy
00043
00044 import tornado.ioloop
00045 import tornado.web
00046
00047
00048 def run_shellcommand(*args):
00049 '''run the provided command and return its stdout'''
00050 args = sum([(arg if type(arg) == list else [arg]) for arg in args], [])
00051 return subprocess.Popen(args,
00052 stdout=subprocess.PIPE).communicate()[0].strip()
00053
00054
00055 def split_words(text):
00056 '''return a list of lines where each line is a list of words'''
00057 return [line.strip().split() for line in text.split('\n')]
00058
00059
00060 def get_packages():
00061 '''
00062 Find the names and locations of all ROS packages
00063
00064 @rtype: {str, str}
00065 @return: name and path of ROS packages
00066 '''
00067 lines = split_words(run_shellcommand('rospack', 'list'))
00068 packages = [{'name': name, 'path': path} for name, path in lines]
00069 return packages
00070
00071
00072 class WebRequestHandler(tornado.web.RequestHandler):
00073
00074 def initialize(self, packages):
00075 '''
00076 @type packages: {str, str}
00077 @param packages: name and path of ROS packages.
00078 '''
00079 self.packages = packages
00080
00081 def get(self):
00082 self.write(
00083 "<h1>ROS web server successfully started.</h1><h3>Package List</h3>")
00084 for package in self.packages:
00085 self.write(
00086 "<div style='font-size: 10px'>" + package['name'] + "</div>")
00087
00088
00089 def create_webserver(packages):
00090 '''
00091 @type packages: {str, str}
00092 @param packages: name and path of ROS packages.
00093 '''
00094 handlers = [(r"/", WebRequestHandler, {"packages": packages})]
00095
00096 for package in packages:
00097 handler_root = ("/" + package['name'] + "/?()",
00098 tornado.web.StaticFileHandler,
00099 {"path": package['path'] + "/www/index.html"})
00100 handlers.append(handler_root)
00101 handler = ("/" + package['name'] + "/(.*)",
00102 tornado.web.StaticFileHandler,
00103 {"path": package['path'] + "/www",
00104 "default_filename": "index.html"})
00105 handlers.append(handler)
00106
00107 rospy.loginfo("Webserver initialized for %d packages", len(packages))
00108 application = tornado.web.Application(handlers)
00109
00110 return application
00111
00112
00113 def bind_webserver(application):
00114 """ See if there's a default port, use 80 if not """
00115 default_port, start_port, end_port = get_webserver_params()
00116
00117 """ First, we try the default http port 80 """
00118 bound = bind_to_port(application, default_port)
00119
00120 if not bound:
00121 """ Otherwise bind any available port within the specified range """
00122 bound = bind_in_range(application, start_port, end_port)
00123
00124 return bound
00125
00126
00127 def get_webserver_params():
00128 try:
00129 default_port = rospy.get_param("http/default", 80)
00130 start_port = rospy.get_param("http/range_start", 8000)
00131 end_port = rospy.get_param("http/range_end", 9000)
00132 return (default_port, start_port, end_port)
00133 except socket.error as err:
00134 if err.errno == 111:
00135
00136 rospy.logwarn("Could not contact ROS master." + \
00137 " Is a roscore running? Error: %s", err.strerror)
00138 return 80, 8000, 9000
00139 else:
00140 raise
00141
00142
00143 def start_webserver(application):
00144 try:
00145 tornado.ioloop.IOLoop.instance().start()
00146 except KeyboardInterrupt:
00147 rospy.loginfo("Webserver shutting down")
00148
00149
00150 def bind_to_port(application, portno):
00151 rospy.loginfo("Attempting to start webserver on port %d", portno)
00152 try:
00153 application.listen(portno)
00154 rospy.loginfo("Webserver successfully started on port %d", portno)
00155 except socket.error as err:
00156
00157 if err.errno == 13:
00158 rospy.logwarn("Insufficient priveliges to run webserver " +
00159 "on port %d. Error: %s", portno, err.strerror)
00160 rospy.loginfo("-- Try re-running as super-user: sudo su; " +
00161 "source ~/.bashrc)")
00162 elif err.errno == 98:
00163 rospy.logwarn("There is already a webserver running on port %d. " +
00164 "Error: %s", portno, err.strerror)
00165 rospy.loginfo("-- Try stopping your web server. For example, " +
00166 "to stop apache: sudo /etc/init.d/apache2 stop")
00167 else:
00168 rospy.logerr("An error occurred attempting to listen on " +
00169 "port %d: %s", portno, err.strerror)
00170 return False
00171 return True
00172
00173
00174 def bind_in_range(application, start_port, end_port):
00175 if (end_port > start_port):
00176 for i in range(start_port, end_port):
00177 if bind_to_port(application, i):
00178 return True
00179 return False
00180
00181
00182 def run_webserver():
00183 try:
00184 packages = get_packages()
00185 server = create_webserver(packages)
00186 bound = bind_webserver(server)
00187 if (bound):
00188 start_webserver(server)
00189 else:
00190 raise Exception()
00191 except Exception as exc:
00192 rospy.logerr("Unable to bind webserver. Exiting. %s" % exc)
00193
00194
00195 if __name__ == '__main__':
00196 run_webserver()