Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 import sys
00011
00012
00013 import rospy
00014 import std_srvs.srv as std_srvs
00015
00016
00017 from . import utils
00018 from . import redis_server
00019 from . import ros_parameters
00020 from . import watcher
00021 from . import zeroconf
00022
00023
00024
00025
00026
00027 redi = None
00028 timeout = 15
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 def ros_service_shutdown(unused_request):
00039 shutdown()
00040 return std_srvs.EmptyResponse()
00041
00042
00043 def shutdown():
00044 global redi
00045 if redi is not None:
00046 rospy.loginfo("Hub : shutting down.")
00047 redi.shutdown()
00048 redi = None
00049
00050
00051 def wait_for_shutdown():
00052 '''
00053 Shutdown hook - we wait here for an external shutdown via ros service
00054 (at which point redi is None)
00055 timing out after a reasonable time if we need to.
00056 '''
00057 global redi
00058 global timeout
00059 count = 0.0
00060 while count < timeout:
00061 if redi is None:
00062 return
00063 else:
00064 count += 0.5
00065 rospy.rostime.wallsleep(0.5)
00066 rospy.logwarn("Hub : timed out waiting for external shutdown by ros service, forcing shutdown now.")
00067 shutdown()
00068
00069
00070
00071
00072
00073
00074
00075 def main():
00076 global redi
00077 global timeout
00078 while not utils.check_master():
00079 rospy.logerr("Unable to communicate with master!")
00080 rospy.rostime.wallsleep(1.0)
00081 if rospy.is_shutdown():
00082 sys.exit(utils.red_string("Unable to communicate with master!"))
00083 rospy.init_node('hub')
00084 param = ros_parameters.load()
00085
00086
00087 utils.check_if_executable_available('redis-server')
00088 if param['zeroconf']:
00089 utils.check_if_executable_available('avahi-daemon')
00090 if param['external_shutdown']:
00091 timeout = param['external_shutdown_timeout']
00092 rospy.on_shutdown(wait_for_shutdown)
00093 unused_shutdown_service = rospy.Service('~shutdown', std_srvs.Empty, ros_service_shutdown)
00094
00095 redi = redis_server.RedisServer(param)
00096 redi.start()
00097
00098 if param['zeroconf']:
00099 zeroconf.advertise_port_to_avahi(param['port'], param['name'])
00100
00101 watcher_thread = watcher.WatcherThread('localhost', param['port'])
00102 watcher_thread.start()
00103 rospy.spin()
00104 if not param['external_shutdown']:
00105
00106 shutdown()