Go to the documentation of this file.00001 import roslib; roslib.load_manifest('iri_common_smach')
00002 import rospy
00003 import smach
00004 import smach_ros
00005 import time
00006
00007 from smach_ros import ServiceState
00008
00009 """
00010 Timed Service State class. Should work as ServiceState but also measures execution time.
00011
00012 USAGE:
00013 User timed_service_state.TimedServiceState instead of ServiceState
00014 """
00015
00016 class TimedServiceState(ServiceState):
00017 """
00018 Timed Service State class. Should work as ServiceState but also measures execution time.
00019 """
00020 def __init__(self, service_name, service_spec, **args):
00021 """
00022 Init method also initializes timer and executions counter
00023 """
00024 ServiceState.__init__(self, service_name = service_name, service_spec = service_spec, **args)
00025 self.total_time = 0
00026 self.num_executions = 0
00027
00028 def execute(self, userdata):
00029 """
00030 Calls inherited execute and measures its execution time
00031 """
00032 init_time = time.time()
00033 self.num_executions += 1
00034 result = super(TimedServiceState, self).execute(userdata)
00035 self.total_time += (time.time() - init_time)
00036 return result
00037
00038 def get_execution_time(self):
00039 return self.total_time
00040
00041 def get_number_executions(self):
00042 return self.num_executions