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 from __future__ import with_statement
00032 import roslib; roslib.load_manifest('actionlib')
00033 import threading
00034 import time
00035 import rospy
00036 from rospy import Header
00037 from actionlib_msgs.msg import *
00038 from action_client import ActionClient, CommState, get_name_of_constant
00039
00040 class SimpleGoalState:
00041 PENDING = 0
00042 ACTIVE = 1
00043 DONE = 2
00044 SimpleGoalState.to_string = classmethod(get_name_of_constant)
00045
00046
00047 class SimpleActionClient:
00048
00049
00050
00051
00052
00053
00054
00055 def __init__(self, ns, ActionSpec):
00056 self.action_client = ActionClient(ns, ActionSpec)
00057 self.simple_state = SimpleGoalState.DONE
00058 self.gh = None
00059 self.done_condition = threading.Condition()
00060
00061
00062
00063
00064
00065
00066
00067 def wait_for_server(self, timeout = rospy.Duration()):
00068 return self.action_client.wait_for_server(timeout)
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085 def send_goal(self, goal, done_cb = None, active_cb = None, feedback_cb = None):
00086
00087 self.stop_tracking_goal()
00088
00089 self.done_cb = done_cb
00090 self.active_cb = active_cb
00091 self.feedback_cb = feedback_cb
00092
00093 self.simple_state = SimpleGoalState.PENDING
00094 self.gh = self.action_client.send_goal(goal, self._handle_transition, self._handle_feedback)
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112 def send_goal_and_wait(self, goal, execute_timeout = rospy.Duration(), preempt_timeout = rospy.Duration()):
00113 self.send_goal(goal)
00114 if not self.wait_for_result(execute_timeout):
00115
00116 rospy.logdebug("Canceling goal")
00117 self.cancel_goal()
00118 if self.wait_for_result(preempt_timeout):
00119 rospy.logdebug("Preempt finished within specified preempt_timeout [%.2f]", preempt_timeout.to_sec());
00120 else:
00121 rospy.logdebug("Preempt didn't finish specified preempt_timeout [%.2f]", preempt_timeout.to_sec());
00122 return self.get_state()
00123
00124
00125
00126
00127
00128 def wait_for_result(self, timeout = rospy.Duration()):
00129 if not self.gh:
00130 rospy.logerr("Called wait_for_goal_to_finish when no goal exists")
00131 return False
00132
00133 timeout_time = rospy.get_rostime() + timeout
00134 loop_period = rospy.Duration(0.1)
00135 with self.done_condition:
00136 while not rospy.is_shutdown():
00137 time_left = timeout_time - rospy.get_rostime()
00138 if timeout > rospy.Duration(0.0) and time_left <= rospy.Duration(0.0):
00139 break
00140
00141 if self.simple_state == SimpleGoalState.DONE:
00142 break
00143
00144 if time_left > loop_period or timeout == rospy.Duration():
00145 time_left = loop_period
00146
00147 self.done_condition.wait(time_left.to_sec())
00148
00149 return self.simple_state == SimpleGoalState.DONE
00150
00151
00152
00153 def get_result(self):
00154 if not self.gh:
00155 rospy.logerr("Called get_result when no goal is running")
00156 return None
00157
00158 return self.gh.get_result()
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168 def get_state(self):
00169 if not self.gh:
00170 rospy.logerr("Called get_state when no goal is running")
00171 return GoalStatus.LOST
00172 status = self.gh.get_goal_status()
00173
00174 if status == GoalStatus.RECALLING:
00175 status = GoalStatus.PENDING
00176 elif status == GoalStatus.PREEMPTING:
00177 status = GoalStatus.ACTIVE
00178
00179 return status
00180
00181
00182
00183
00184
00185
00186
00187
00188 def get_goal_status_text(self):
00189 if not self.gh:
00190 rospy.logerr("Called get_goal_status_text when no goal is running")
00191 return "ERROR: Called get_goal_status_text when no goal is running"
00192
00193 return self.gh.get_goal_status_text()
00194
00195
00196
00197
00198
00199
00200
00201
00202 def cancel_all_goals(self):
00203 self.action_client.cancel_all_goals()
00204
00205
00206
00207
00208
00209
00210
00211
00212 def cancel_goals_at_and_before_time(self, time):
00213 self.action_client.cancel_goals_at_and_before_time(time)
00214
00215
00216
00217 def cancel_goal(self):
00218 if self.gh:
00219 self.gh.cancel()
00220
00221
00222
00223
00224
00225
00226 def stop_tracking_goal(self):
00227 self.gh = None
00228
00229 def _handle_transition(self, gh):
00230 comm_state = gh.get_comm_state()
00231
00232 error_msg = "Received comm state %s when in simple state %s with SimpleActionClient in NS %s" % \
00233 (CommState.to_string(comm_state), SimpleGoalState.to_string(self.simple_state), rospy.resolve_name(self.action_client.ns))
00234
00235 if comm_state == CommState.ACTIVE:
00236 if self.simple_state == SimpleGoalState.PENDING:
00237 self._set_simple_state(SimpleGoalState.ACTIVE)
00238 if self.active_cb:
00239 self.active_cb()
00240 elif self.simple_state == SimpleGoalState.DONE:
00241 rospy.logerr(error_msg)
00242 elif comm_state == CommState.RECALLING:
00243 if self.simple_state != SimpleGoalState.PENDING:
00244 rospy.logerr(error_msg)
00245 elif comm_state == CommState.PREEMPTING:
00246 if self.simple_state == SimpleGoalState.PENDING:
00247 self._set_simple_state(SimpleGoalState.ACTIVE)
00248 if self.active_cb:
00249 self.active_cb()
00250 elif self.simple_state == SimpleGoalState.DONE:
00251 rospy.logerr(error_msg)
00252 elif comm_state == CommState.DONE:
00253 if self.simple_state in [SimpleGoalState.PENDING, SimpleGoalState.ACTIVE]:
00254 self._set_simple_state(SimpleGoalState.DONE)
00255 if self.done_cb:
00256 self.done_cb(gh.get_goal_status(), gh.get_result())
00257 with self.done_condition:
00258 self.done_condition.notifyAll()
00259 elif self.simple_state == SimpleGoalState.DONE:
00260 rospy.logerr("SimpleActionClient received DONE twice")
00261
00262 def _handle_feedback(self, gh, feedback):
00263 if not self.gh:
00264 rospy.logerr("Got a feedback callback when we're not tracking a goal. (id: %s)" % \
00265 gh.comm_state_machine.action_goal.goal_id.id)
00266 return
00267 if gh != self.gh:
00268 rospy.logerr("Got a feedback callback on a goal handle that we're not tracking. %s vs %s" % \
00269 (self.gh.comm_state_machine.action_goal.goal_id.id,
00270 gh.comm_state_machine.action_goal.goal_id.id))
00271 return
00272 if self.feedback_cb:
00273 self.feedback_cb(feedback)
00274
00275
00276 def _set_simple_state(self, state):
00277 self.simple_state = state