Go to the documentation of this file.00001
00002
00003 """
00004 Copyright (c) 2013,
00005 Systems, Robotics and Vision Group
00006 University of the Balearican Islands
00007 All rights reserved.
00008
00009 Redistribution and use in source and binary forms, with or without
00010 modification, are permitted provided that the following conditions are met:
00011 * Redistributions of source code must retain the above copyright
00012 notice, this list of conditions and the following disclaimer.
00013 * Redistributions in binary form must reproduce the above copyright
00014 notice, this list of conditions and the following disclaimer in the
00015 documentation and/or other materials provided with the distribution.
00016 * Neither the name of Systems, Robotics and Vision Group, University of
00017 the Balearican Islands nor the names of its contributors may be used to
00018 endorse or promote products derived from this software without specific
00019 prior written permission.
00020
00021 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00022 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00023 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00024 DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00025 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00026 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00028 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00029 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00030 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00031 """
00032
00033
00034
00035 import roslib; roslib.load_manifest('launch_tools')
00036 import sys
00037 import rospy
00038 import rosservice
00039 import threading
00040
00041
00042
00043 class TimedService(threading.Thread):
00044
00045
00046
00047
00048
00049 def __init__(self, name, period):
00050 threading.Thread.__init__(self)
00051 self._service_name = name
00052 self._service_period = period
00053
00054
00055 def run(self):
00056 rospy.wait_for_service(self._service_name)
00057 rospy.Timer(rospy.Duration(self._service_period), self.callback)
00058 rospy.loginfo('Initialized timer for service: \n\t* Name: %s\n\t* Period: %f ', self._service_name, self._service_period)
00059
00060
00061
00062 def callback(self,event):
00063 rospy.wait_for_service(self._service_name)
00064 service_class = rosservice.get_service_class_by_name(self._service_name)
00065 try:
00066 service = rospy.ServiceProxy(self._service_name,service_class)
00067 service()
00068 rospy.loginfo('Service %s called.', self._service_name)
00069 except rospy.ServiceException, e:
00070 rospy.logwarn('Service %s call failed: %s',self._service_name,e)
00071
00072
00073
00074 _service_name = "service"
00075
00076
00077
00078 _service_period = 1.0
00079
00080
00081 def usage():
00082 return "%s service period [service period ...]"%sys.argv[0]
00083
00084
00085 if __name__ == "__main__":
00086 rospy.init_node('services_timer')
00087 if len(sys.argv) >= 3:
00088 names = sys.argv[1:len(sys.argv):2]
00089 periods = sys.argv[2:len(sys.argv):2]
00090 rospy.loginfo('names : %s', names)
00091 rospy.loginfo('periods : %s', periods)
00092 ts_list = []
00093 for name,period in zip(names,periods):
00094 ts_list.append(TimedService(str(name), float(period)))
00095 for ts in ts_list:
00096 ts.start()
00097 else:
00098 rospy.loginfo(usage())
00099 sys.exit(1)
00100 rospy.spin()