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 from __future__ import with_statement
00033
00034 import roslib; roslib.load_manifest('actionlib')
00035 import rospy
00036
00037 import sys
00038
00039
00040 from actionlib_msgs.msg import GoalID
00041 import threading
00042
00043 global s_goalcount_lock
00044 global s_goalcount
00045 s_goalcount_lock = threading.Lock();
00046 s_goalcount = 0
00047
00048
00049 class GoalIDGenerator:
00050
00051
00052 def __init__(self,name=None):
00053 """
00054 * Create a generator that prepends the fully qualified node name to the Goal ID
00055 * \param name Unique name to prepend to the goal id. This will
00056 * generally be a fully qualified node name.
00057 """
00058 if name is not None:
00059 self.set_name(name)
00060 else:
00061 self.set_name(rospy.get_name());
00062
00063
00064 def set_name(self,name):
00065 """
00066 * \param name Set the name to prepend to the goal id. This will
00067 * generally be a fully qualified node name.
00068 """
00069 self.name=name;
00070
00071
00072
00073 def generate_ID(self):
00074 """
00075 * \brief Generates a unique ID
00076 * \return A unique GoalID for this action
00077 """
00078 id = GoalID();
00079 cur_time = rospy.Time.now();
00080 ss = self.name + "-";
00081 global s_goalcount_lock
00082 global s_goalcount
00083 with s_goalcount_lock:
00084 s_goalcount += 1
00085 ss += str(s_goalcount) + "-";
00086 ss += str(cur_time.secs) + "." + str(cur_time.nsecs);
00087
00088 id.id = ss;
00089 id.stamp = cur_time;
00090 return id;