$search
00001 #! /usr/bin/env python 00002 # Copyright (c) 2009, Willow Garage, Inc. 00003 # All rights reserved. 00004 # 00005 # Redistribution and use in source and binary forms, with or without 00006 # modification, are permitted provided that the following conditions are met: 00007 # 00008 # * Redistributions of source code must retain the above copyright 00009 # notice, this list of conditions and the following disclaimer. 00010 # * Redistributions in binary form must reproduce the above copyright 00011 # notice, this list of conditions and the following disclaimer in the 00012 # documentation and/or other materials provided with the distribution. 00013 # * Neither the name of the Willow Garage, Inc. nor the names of its 00014 # contributors may be used to endorse or promote products derived from 00015 # this software without specific prior written permission. 00016 # 00017 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 # POSSIBILITY OF SUCH DAMAGE. 00028 00029 # Author: Alexander Sorokin. 00030 # Based on C++ goal_id_generator.h/cpp 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;