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 Queue
38 
39 from actionlib_msgs.msg import *
40 
41 from actionlib import ActionServer
42 from actionlib.server_goal_handle import ServerGoalHandle;
43 
44 def nop_cb(goal_handle):
45  pass
46 
47 
48 ## @class ComplexActionServer
49 ## @brief The ComplexActionServer
50 ## Operate with concurrent goals in a multi-threaded fashion
52  ## @brief Constructor for a ComplexActionServer
53  ## @param name A name for the action server
54  ## @param execute_cb Optional callback that gets called in a separate thread whenever
55  ## a new goal is received, allowing users to have blocking callbacks.
56  ## Adding an execute callback also deactivates the goalCallback.
57  ## @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.
58  def __init__(self, name, ActionSpec, execute_cb = None, auto_start = True):
59 
60  self.goals_received_ = 0;
61  self.goal_queue_ = Queue.Queue()
62 
63  self.new_goal = False
64 
65  self.execute_callback = execute_cb;
66  self.goal_callback = None;
67 
68  self.need_to_terminate = False
69  self.terminate_mutex = threading.RLock();
70 
71  # since the internal_goal/preempt_callbacks are invoked from the
72  # ActionServer while holding the self.action_server.lock
73  # self.lock must always be locked after the action server lock
74  # to avoid an inconsistent lock acquisition order
75  self.lock = threading.RLock();
76 
77  self.execute_condition = threading.Condition(self.lock);
78 
81 
82  if self.execute_callback:
83  self.execute_thread = threading.Thread(None, self.executeLoop);
84  self.execute_thread.start();
85  else:
86  self.execute_thread = None
87 
88 
89  #create the action server
90  self.action_server = ActionServer(name, ActionSpec, self.internal_goal_callback,self.internal_preempt_callback,auto_start);
91 
92 
93  def __del__(self):
94  if hasattr(self, 'execute_callback') and self.execute_callback:
95  with self.terminate_mutex:
96  self.need_to_terminate = True;
97 
98  assert(self.execute_thread);
99  self.execute_thread.join();
100 
101 
102  ## @brief Accepts a new goal when one is available The status of this
103  ## goal is set to active upon acceptance,
104  def accept_new_goal(self):
105  with self.action_server.lock, self.lock:
106 
107  rospy.logdebug("Accepting a new goal");
108 
109  self.goals_received_ -= 1;
110 
111  #get from queue
112  current_goal = self.goal_queue_.get()
113 
114  #set the status of the current goal to be active
115  current_goal.set_accepted("This goal has been accepted by the simple action server");
116 
117  return current_goal#.get_goal();
118 
119 
120  ## @brief Allows polling implementations to query about the availability of a new goal
121  ## @return True if a new goal is available, false otherwise
123  return self.goals_received_ > 0
124 
125 
126  ## @brief Allows polling implementations to query about the status of the current goal
127  ## @return True if a goal is active, false otherwise
128  def is_active(self):
129  if not self.current_goal.get_goal():
130  return False;
131 
132  status = self.current_goal.get_goal_status().status;
133  return status == actionlib_msgs.msg.GoalStatus.ACTIVE #or status == actionlib_msgs.msg.GoalStatus.PREEMPTING;
134 
135  ## @brief Sets the status of the active goal to succeeded
136  ## @param result An optional result to send back to any clients of the goal
137  def set_succeeded(self,result=None, text="", goal_handle=None):
138  with self.action_server.lock, self.lock:
139  if not result:
140  result=self.get_default_result();
141  #self.current_goal.set_succeeded(result, text);
142  goal_handle.set_succeeded(result,text)
143 
144  ## @brief Sets the status of the active goal to aborted
145  ## @param result An optional result to send back to any clients of the goal
146  def set_aborted(self, result = None, text="" , goal_handle=None):
147  with self.action_server.lock, self.lock:
148  if not result:
149  result=self.get_default_result();
150  #self.current_goal.set_aborted(result, text);
151  goal_handle.set_aborted(result,text)
152 
153  ## @brief Publishes feedback for a given goal
154  ## @param feedback Shared pointer to the feedback to publish
155  def publish_feedback(self,feedback):
156  self.current_goal.publish_feedback(feedback);
157 
158 
160  return self.action_server.ActionResultType();
161 
162  ## @brief Allows users to register a callback to be invoked when a new goal is available
163  ## @param cb The callback to be invoked
165  if self.execute_callback:
166  rospy.logwarn("Cannot call ComplexActionServer.register_goal_callback() because an executeCallback exists. Not going to register it.");
167  else:
168  self.goal_callback = cb;
169 
170 
171  ## @brief Explicitly start the action server, used it auto_start is set to false
172  def start(self):
173  self.action_server.start();
174 
175 
176  ## @brief Callback for when the ActionServer receives a new goal and passes it on
177  def internal_goal_callback(self, goal):
178  self.execute_condition.acquire();
179 
180  try:
181  rospy.logdebug("A new goal %shas been recieved by the single goal action server",goal.get_goal_id().id);
182 
183 
184  print "got a goal"
185  self.next_goal = goal;
186  self.new_goal = True;
187  self.goals_received_ += 1
188 
189  #add goal to queue
190  self.goal_queue_.put(goal)
191 
192  #Trigger runLoop to call execute()
193  self.execute_condition.notify();
194  self.execute_condition.release();
195 
196  except Exception, e:
197  rospy.logerr("ComplexActionServer.internal_goal_callback - exception %s",str(e))
198  self.execute_condition.release();
199 
200 
201  ## @brief Callback for when the ActionServer receives a new preempt and passes it on
202  def internal_preempt_callback(self,preempt):
203  return
204 
205  ## @brief Called from a separate thread to call blocking execute calls
206  def executeLoop(self):
207  loop_duration = rospy.Duration.from_sec(.1);
208 
209  while (not rospy.is_shutdown()):
210  rospy.logdebug("SAS: execute");
211 
212  with self.terminate_mutex:
213  if (self.need_to_terminate):
214  break;
215 
216  if (self.is_new_goal_available()):
217  # accept_new_goal() is performing its own locking
218  goal_handle = self.accept_new_goal();
219  if not self.execute_callback:
220  rospy.logerr("execute_callback_ must exist. This is a bug in ComplexActionServer");
221  return
222 
223  try:
224 
225  print "run new executecb"
226  thread = threading.Thread(target=self.run_goal,args=(goal_handle.get_goal(),goal_handle));
227  thread.start()
228 
229  except Exception, ex:
230  rospy.logerr("Exception in your execute callback: %s\n%s", str(ex),
231  traceback.format_exc())
232  self.set_aborted(None, "Exception in execute callback: %s" % str(ex))
233 
234  with self.execute_condition:
235  self.execute_condition.wait(loop_duration.to_sec());
236 
237 
238 
239 
240  def run_goal(self,goal, goal_handle):
241  print 'new thread'
242  self.execute_callback(goal,goal_handle);
243 
244 
245 
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 Wed Jun 5 2019 21:52:01