complex_action_server.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # Copyright (c) 2009, Willow Garage, Inc.
3 # All rights reserved.
4 #
5 # Redistribution and use in source and binary forms, with or without
6 # modification, are permitted provided that the following conditions are met:
7 #
8 # * Redistributions of source code must retain the above copyright
9 # notice, this list of conditions and the following disclaimer.
10 # * Redistributions in binary form must reproduce the above copyright
11 # notice, this list of conditions and the following disclaimer in the
12 # documentation and/or other materials provided with the distribution.
13 # * Neither the name of the Willow Garage, Inc. nor the names of its
14 # contributors may be used to endorse or promote products derived from
15 # this software without specific prior written permission.
16 #
17 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 # POSSIBILITY OF SUCH DAMAGE.
28 #
29 # Author: Brian Wright.
30 # Based on C++ simple_action_server.h by Eitan Marder-Eppstein
31 
32 import rospy
33 
34 import threading
35 import traceback
36 
37 import six
38 
39 import actionlib_msgs
40 from actionlib import ActionServer
41 from actionlib.server_goal_handle import ServerGoalHandle;
42 
43 def nop_cb(goal_handle):
44  pass
45 
46 
47 ## @class ComplexActionServer
48 ## @brief The ComplexActionServer
49 ## Operate with concurrent goals in a multi-threaded fashion
51  ## @brief Constructor for a ComplexActionServer
52  ## @param name A name for the action server
53  ## @param execute_cb Optional callback that gets called in a separate thread whenever
54  ## a new goal is received, allowing users to have blocking callbacks.
55  ## Adding an execute callback also deactivates the goalCallback.
56  ## @param auto_start A boolean value that tells the ActionServer wheteher or not to start publishing as soon as it comes up. THIS SHOULD ALWAYS BE SET TO FALSE TO AVOID RACE CONDITIONS and start() should be called after construction of the server.
57  def __init__(self, name, ActionSpec, execute_cb = None, auto_start = True):
58 
59  self.goals_received_ = 0;
60  self.goal_queue_ = six.moves.queue.Queue()
61 
62  self.new_goal = False
63 
64  self.execute_callback = execute_cb;
65  self.goal_callback = None;
66 
67  self.need_to_terminate = False
68  self.terminate_mutex = threading.RLock();
69 
70  # since the internal_goal/preempt_callbacks are invoked from the
71  # ActionServer while holding the self.action_server.lock
72  # self.lock must always be locked after the action server lock
73  # to avoid an inconsistent lock acquisition order
74  self.lock = threading.RLock();
75 
76  self.execute_condition = threading.Condition(self.lock);
77 
80 
81  if self.execute_callback:
82  self.execute_thread = threading.Thread(None, self.executeLoop);
83  self.execute_thread.start();
84  else:
85  self.execute_thread = None
86 
87 
88  #create the action server
89  self.action_server = ActionServer(name, ActionSpec, self.internal_goal_callback,self.internal_preempt_callback,auto_start);
90 
91 
92  def __del__(self):
93  if hasattr(self, 'execute_callback') and self.execute_callback:
94  with self.terminate_mutex:
95  self.need_to_terminate = True;
96 
97  assert(self.execute_thread);
98  self.execute_thread.join();
99 
100 
101  ## @brief Accepts a new goal when one is available The status of this
102  ## goal is set to active upon acceptance,
103  def accept_new_goal(self):
104  with self.action_server.lock, self.lock:
105 
106  rospy.logdebug("Accepting a new goal");
107 
108  self.goals_received_ -= 1;
109 
110  #get from queue
111  current_goal = self.goal_queue_.get()
112 
113  #set the status of the current goal to be active
114  current_goal.set_accepted("This goal has been accepted by the simple action server");
115 
116  return current_goal#.get_goal();
117 
118 
119  ## @brief Allows polling implementations to query about the availability of a new goal
120  ## @return True if a new goal is available, false otherwise
122  return self.goals_received_ > 0
123 
124 
125  ## @brief Allows polling implementations to query about the status of the current goal
126  ## @return True if a goal is active, false otherwise
127  def is_active(self):
128  if not self.current_goal.get_goal():
129  return False;
130 
131  status = self.current_goal.get_goal_status().status;
132  return status == actionlib_msgs.msg.GoalStatus.ACTIVE #or status == actionlib_msgs.msg.GoalStatus.PREEMPTING;
133 
134  ## @brief Sets the status of the active goal to succeeded
135  ## @param result An optional result to send back to any clients of the goal
136  def set_succeeded(self,result=None, text="", goal_handle=None):
137  with self.action_server.lock, self.lock:
138  if not result:
139  result=self.get_default_result();
140  #self.current_goal.set_succeeded(result, text);
141  goal_handle.set_succeeded(result,text)
142 
143  ## @brief Sets the status of the active goal to aborted
144  ## @param result An optional result to send back to any clients of the goal
145  def set_aborted(self, result = None, text="" , goal_handle=None):
146  with self.action_server.lock, self.lock:
147  if not result:
148  result=self.get_default_result();
149  #self.current_goal.set_aborted(result, text);
150  goal_handle.set_aborted(result,text)
151 
152  ## @brief Publishes feedback for a given goal
153  ## @param feedback Shared pointer to the feedback to publish
154  def publish_feedback(self,feedback):
155  self.current_goal.publish_feedback(feedback);
156 
157 
159  return self.action_server.ActionResultType();
160 
161  ## @brief Allows users to register a callback to be invoked when a new goal is available
162  ## @param cb The callback to be invoked
164  if self.execute_callback:
165  rospy.logwarn("Cannot call ComplexActionServer.register_goal_callback() because an executeCallback exists. Not going to register it.");
166  else:
167  self.goal_callback = cb;
168 
169 
170  ## @brief Explicitly start the action server, used it auto_start is set to false
171  def start(self):
172  self.action_server.start();
173 
174 
175  ## @brief Callback for when the ActionServer receives a new goal and passes it on
176  def internal_goal_callback(self, goal):
177  self.execute_condition.acquire();
178 
179  try:
180  rospy.logdebug("A new goal %shas been recieved by the single goal action server",goal.get_goal_id().id);
181 
182 
183  print("got a goal")
184  self.next_goal = goal;
185  self.new_goal = True;
186  self.goals_received_ += 1
187 
188  #add goal to queue
189  self.goal_queue_.put(goal)
190 
191  #Trigger runLoop to call execute()
192  self.execute_condition.notify();
193  self.execute_condition.release();
194 
195  except Exception as e:
196  rospy.logerr("ComplexActionServer.internal_goal_callback - exception %s",str(e))
197  self.execute_condition.release();
198 
199 
200  ## @brief Callback for when the ActionServer receives a new preempt and passes it on
201  def internal_preempt_callback(self,preempt):
202  return
203 
204  ## @brief Called from a separate thread to call blocking execute calls
205  def executeLoop(self):
206  loop_duration = rospy.Duration.from_sec(.1);
207 
208  while (not rospy.is_shutdown()):
209  rospy.logdebug("SAS: execute");
210 
211  with self.terminate_mutex:
212  if (self.need_to_terminate):
213  break;
214 
215  if (self.is_new_goal_available()):
216  # accept_new_goal() is performing its own locking
217  goal_handle = self.accept_new_goal();
218  if not self.execute_callback:
219  rospy.logerr("execute_callback_ must exist. This is a bug in ComplexActionServer");
220  return
221 
222  try:
223 
224  print("run new executecb")
225  thread = threading.Thread(target=self.run_goal,args=(goal_handle.get_goal(),goal_handle));
226  thread.start()
227 
228  except Exception as ex:
229  rospy.logerr("Exception in your execute callback: %s\n%s", str(ex),
230  traceback.format_exc())
231  self.set_aborted(None, "Exception in execute callback: %s" % str(ex))
232 
233  with self.execute_condition:
234  self.execute_condition.wait(loop_duration.to_sec());
235 
236 
237 
238 
239  def run_goal(self,goal, goal_handle):
240  print('new thread')
241  self.execute_callback(goal,goal_handle);
242 
243 
244 
def __init__(self, name, ActionSpec, execute_cb=None, auto_start=True)
Constructor for a ComplexActionServer.
def internal_preempt_callback(self, preempt)
Callback for when the ActionServer receives a new preempt and passes it on.
def set_succeeded(self, result=None, text="", goal_handle=None)
Sets the status of the active goal to succeeded.
def register_goal_callback(self, cb)
Allows users to register a callback to be invoked when a new goal is available.
def start(self)
Explicitly start the action server, used it auto_start is set to false.
def set_aborted(self, result=None, text="", goal_handle=None)
Sets the status of the active goal to aborted.
def internal_goal_callback(self, goal)
Callback for when the ActionServer receives a new goal and passes it on.
def executeLoop(self)
Called from a separate thread to call blocking execute calls.
The ComplexActionServer Operate with concurrent goals in a multi-threaded fashion.
def accept_new_goal(self)
Accepts a new goal when one is available The status of this goal is set to active upon acceptance...
def publish_feedback(self, feedback)
Publishes feedback for a given goal.
def is_active(self)
Allows polling implementations to query about the status of the current goal.
def is_new_goal_available(self)
Allows polling implementations to query about the availability of a new goal.


flexbe_input
Author(s): Philipp Schillinger
autogenerated on Sun Dec 13 2020 04:01:40