redis_server.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # License: BSD
00004 #   https://raw.github.com/robotics-in-concert/rocon_multimaster/license/LICENSE
00005 #
00006 ##############################################################################
00007 # Imports
00008 ##############################################################################
00009 
00010 import os
00011 import sys
00012 import re
00013 import shutil
00014 import subprocess
00015 import signal
00016 
00017 # Delete this once we upgrade (hopefully anything after precise)
00018 # Refer to https://github.com/robotics-in-concert/rocon_multimaster/issues/248
00019 import threading
00020 threading._DummyThread._Thread__stop = lambda x: 42
00021 
00022 import rospy
00023 import rospkg
00024 try:
00025     import rocon_python_redis as redis
00026 except ImportError:
00027     # actually unused right now while we use redis as a ros package
00028     sys.exit("\n[ERROR] No python-redis found - 'rosdep install rocon_hub'\n")
00029 import rocon_semantic_version as semantic_version
00030 
00031 from . import utils
00032 
00033 ##############################################################################
00034 # Redis Server
00035 ##############################################################################
00036 
00037 
00038 class RedisServer:
00039     def __init__(self, parameters):
00040         self._parameters = parameters
00041         self._process = None
00042         self._home_dir = os.path.join(rospkg.get_ros_home(), 'redis', self._parameters['name'].lower().replace(" ", "_"))
00043         # clean out old redis information
00044         if os.path.isdir(self._home_dir):
00045             shutil.rmtree(self._home_dir)
00046         self._files = {}
00047         self._version_extension = self._introspect_redis_server_version()
00048         self._files['redis_conf'] = os.path.join(self._home_dir, 'redis-%s.conf' % self._version_extension)
00049         self._files['redis_conf_local'] = os.path.join(self._home_dir, 'redis-%s.conf.local' % self._version_extension)
00050         self._files['redis_server_log'] = os.path.join(self._home_dir, 'redis-server.log')
00051         self._server = None
00052         self._setup()
00053 
00054     def _introspect_redis_server_version(self):
00055         '''
00056           Sniff the version in major.minor format for decision making elsewhere (patch we disregard since our
00057           decisions don't depend on it).
00058 
00059           @return version extension in 'major.minor' format.
00060           @rtype str
00061         '''
00062         process = subprocess.Popen(["redis-server", "--version"], stdout=subprocess.PIPE, stderr=subprocess.PIPE)
00063         output, unused_error = process.communicate()
00064         try:
00065             version_string = re.search('v=([0-9.]+)', output).group(1)  # 2.6+ pattern
00066         except AttributeError:
00067             version_string = re.search('version ([0-9.]+)', output).group(1)  # 2.2 pattern
00068         version = semantic_version.Version(version_string)
00069         rospy.loginfo("Hub : version %s" % (version_string))
00070         return str(version.major) + "." + str(version.minor)
00071 
00072     def _setup(self):
00073         '''
00074           Clear and configure redis conf, log files in the ros home
00075           directories under a subdirectory styled by the name of this hub.
00076 
00077           Also check that we have support for the redis server - i.e. check if we
00078           have a .conf file for that version and exit this script if not found.
00079         '''
00080         if os.path.isdir(self._home_dir):
00081             shutil.rmtree(self._home_dir)
00082         os.makedirs(self._home_dir)
00083         rospack = rospkg.RosPack()
00084         package_redis_conf_file = os.path.join(rospack.get_path('rocon_hub'), 'redis', 'redis-%s.conf' % self._version_extension)
00085         package_redis_conf_local_file = os.path.join(rospack.get_path('rocon_hub'), 'redis', 'redis-%s.conf.local' % self._version_extension)
00086 
00087         # Checks
00088         if not os.path.isfile(package_redis_conf_file):
00089             utils.logfatal("Hub : the version of the redis server you have installed is not supported by rocon.")
00090             sys.exit(utils.logfatal("Hub : please submit a ticket at https://github.com/robotics-in-concert/rocon_multimaster"))
00091 
00092         redis_conf_template = utils.read_template(package_redis_conf_file)
00093         redis_conf_template = instantiate_redis_conf_template(redis_conf_template, self._files['redis_conf_local'])  # drop the local file path to use into the settings
00094         redis_local_template = utils.read_template(package_redis_conf_local_file)
00095         redis_local_template = instantiate_local_conf_template(redis_local_template,
00096                                                                self._parameters['port'],
00097                                                                self._parameters['max_memory'],
00098                                                                self._files['redis_server_log'],
00099                                                                self._home_dir)
00100         try:
00101             f = open(self._files['redis_conf'], 'w')
00102             f.write(redis_conf_template.encode('utf-8'))
00103         finally:
00104             f.close()
00105         try:
00106             f = open(self._files['redis_conf_local'], 'w')
00107             f.write(redis_local_template.encode('utf-8'))
00108         finally:
00109             f.close()
00110 
00111     def start(self):
00112         '''
00113           Start the server. Also connect, delete all rocon:xxx
00114           variables and reinitialise with specified values.
00115 
00116           Aborts the program if the connection fails.
00117         '''
00118         # Launch as a separate process group so we can control when it gets shut down.
00119         self._process = subprocess.Popen(["redis-server", self._files['redis_conf']], preexec_fn=os.setpgrp)
00120         pool = redis.ConnectionPool(host='localhost', port=int(self._parameters['port']), db=0)
00121         no_attempts = 5
00122         count = 0
00123         while count < no_attempts:
00124             try:
00125                 self._server = redis.Redis(connection_pool=pool)
00126                 rocon_keys = self._server.keys("rocon:*")
00127                 pattern = re.compile("rocon:*")
00128                 keys_to_delete = []
00129                 for key in rocon_keys:
00130                     if pattern.match(key):
00131                         keys_to_delete.append(key)
00132                 pipe = self._server.pipeline()
00133                 if len(keys_to_delete) != 0:
00134                     pipe.delete(*keys_to_delete)  # * unpacks the list args - http://stackoverflow.com/questions/2921847/python-once-and-for-all-what-does-the-star-operator-mean-in-python
00135                 pipe.set("rocon:hub:name", self._parameters['name'])
00136                 pipe.execute()
00137                 rospy.loginfo("Hub : reset hub variables on the redis server.")
00138                 break
00139             except redis.ConnectionError:
00140                 count += 1
00141                 if count == no_attempts:
00142                     self.shutdown()
00143                     sys.exit(utils.logfatal("Hub : could not connect to the redis server - is it running?"))
00144                 else:
00145                     rospy.rostime.wallsleep(0.1)
00146 
00147     def shutdown(self):
00148         '''
00149           Clears rocon: keys on the server.
00150         '''
00151         try:
00152             rocon_keys = self._server.keys("rocon:*")
00153             pattern = re.compile("rocon:*")
00154             keys_to_delete = []
00155             for key in rocon_keys:
00156                 if pattern.match(key):
00157                     keys_to_delete.append(key)
00158             pipe = self._server.pipeline()
00159             if len(keys_to_delete) != 0:
00160                 pipe.delete(*keys_to_delete)  # * unpacks the list args - http://stackoverflow.com/questions/2921847/python-once-and-for-all-what-does-the-star-operator-mean-in-python
00161             pipe.execute()
00162             #rospy.loginfo("Hub : clearing hub variables on the redis server.")
00163         except redis.ConnectionError:
00164             pass
00165         try:
00166             # because we start the redis sserver as a separate process group, we need to handle its shutdown
00167             # as roslaunch knows nothing of it.
00168             self._process.send_signal(signal.SIGINT)
00169             self._process.wait()
00170         except OSError:
00171             pass  # process already shut down
00172 
00173 
00174 ##############################################################################
00175 # Functions
00176 ##############################################################################
00177 
00178 
00179 def instantiate_redis_conf_template(template, local_conf_filename):
00180     '''
00181       Variable substitution in a template file.
00182 
00183       @param local_conf_filename : where to find the local redis configuration file
00184       @type string
00185     '''
00186     return template % locals()
00187 
00188 
00189 def instantiate_local_conf_template(template, port, max_memory, logfile, working_dir):
00190     '''
00191       Variable substitution in a template file.
00192 
00193       @param port : port on which the server will run
00194       @type int
00195       @param pid_file : pathname to where the pid file will be stored
00196       @type string
00197       @param max_memory: how much memory to allocate to the redis server in bytes
00198       @type string (e.g. 10mb)
00199       @param logfile
00200       @type string
00201       @param working_dir : filesystem which redis uses to dump (can we turn this off in 2.6?)
00202       @type string
00203     '''
00204     return template % locals()
00205 
00206 if __name__ == "__main__":
00207     pool = redis.ConnectionPool(host='localhost', port='6380', db=0)
00208     try:
00209         print "dude"
00210     except redis.exceptions.ConnectionError:
00211         print "err"


rocon_hub
Author(s): Daniel Stonier , Jihoon Lee , Piyush Khandelwal
autogenerated on Sat Jun 8 2019 18:48:46