33 from move_base.msg import * 34 rospy.init_node('foo') 37 from move_base.msg import * 38 from geometry_msgs.msg import * 39 g1 = MoveBaseGoal(PoseStamped(Header(frame_id = 'base_link'), 41 Quaternion(0, 0, 0, 1)))) 42 g2 = MoveBaseGoal(PoseStamped(Header(frame_id = 'base_link'), 44 Quaternion(0, 0, 0, 1)))) 46 client = ActionClient('move_base', MoveBaseAction) 48 h1 = client.send_goal(g1) 49 h2 = client.send_goal(g2) 50 client.cancel_all_goals() 57 from rospy
import Header
58 from actionlib_msgs.msg
import GoalID, GoalStatus, GoalStatusArray
65 for k, v
in C.__dict__.items():
66 if isinstance(v, int)
and v == n:
68 return "NO_SUCH_STATE_%d" % n
72 WAITING_FOR_GOAL_ACK = 0
75 WAITING_FOR_RESULT = 3
76 WAITING_FOR_CANCEL_ACK = 4
84 RECALLED = GoalStatus.RECALLED
85 REJECTED = GoalStatus.REJECTED
86 PREEMPTED = GoalStatus.PREEMPTED
87 ABORTED = GoalStatus.ABORTED
88 SUCCEEDED = GoalStatus.SUCCEEDED
89 LOST = GoalStatus.LOST
92 GoalStatus.to_string = classmethod(get_name_of_constant)
93 CommState.to_string = classmethod(get_name_of_constant)
94 TerminalState.to_string = classmethod(get_name_of_constant)
98 for s
in status_array.status_list:
99 if s.goal_id.id == id:
140 with self.comm_state_machine.mutex:
141 cancel_msg = GoalID(stamp=rospy.Time(0),
142 id=self.comm_state_machine.action_goal.goal_id.id)
143 self.comm_state_machine.send_cancel_fn(cancel_msg)
144 self.comm_state_machine.transition_to(CommState.WAITING_FOR_CANCEL_ACK)
154 rospy.logerr(
"Trying to get_comm_state on an inactive ClientGoalHandle.")
155 return CommState.LOST
156 return self.comm_state_machine.state
166 rospy.logerr(
"Trying to get_goal_status on an inactive ClientGoalHandle.")
167 return GoalStatus.PENDING
168 return self.comm_state_machine.latest_goal_status.status
177 rospy.logerr(
"Trying to get_goal_status_text on an inactive ClientGoalHandle.")
178 return "ERROR: Trying to get_goal_status_text on an inactive ClientGoalHandle." 179 return self.comm_state_machine.latest_goal_status.text
186 rospy.logerr(
"Trying to get_result on an inactive ClientGoalHandle.")
188 if not self.comm_state_machine.latest_result:
191 return self.comm_state_machine.latest_result.result
201 rospy.logerr(
"Trying to get_terminal_state on an inactive ClientGoalHandle.")
202 return GoalStatus.LOST
204 with self.comm_state_machine.mutex:
205 if self.comm_state_machine.state != CommState.DONE:
206 rospy.logwarn(
"Asking for the terminal state when we're in [%s]",
207 CommState.to_string(self.comm_state_machine.state))
209 goal_status = self.comm_state_machine.latest_goal_status.status
210 if goal_status
in [GoalStatus.PREEMPTED, GoalStatus.SUCCEEDED,
211 GoalStatus.ABORTED, GoalStatus.REJECTED,
212 GoalStatus.RECALLED, GoalStatus.LOST]:
215 rospy.logerr(
"Asking for a terminal state, but the goal status is %d", goal_status)
216 return GoalStatus.LOST
220 INVALID_TRANSITION = -2
222 CommState.WAITING_FOR_GOAL_ACK: {
223 GoalStatus.PENDING: CommState.PENDING,
224 GoalStatus.ACTIVE: CommState.ACTIVE,
225 GoalStatus.REJECTED: (CommState.PENDING, CommState.WAITING_FOR_RESULT),
226 GoalStatus.RECALLING: (CommState.PENDING, CommState.RECALLING),
227 GoalStatus.RECALLED: (CommState.PENDING, CommState.WAITING_FOR_RESULT),
228 GoalStatus.PREEMPTED: (CommState.ACTIVE, CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
229 GoalStatus.SUCCEEDED: (CommState.ACTIVE, CommState.WAITING_FOR_RESULT),
230 GoalStatus.ABORTED: (CommState.ACTIVE, CommState.WAITING_FOR_RESULT),
231 GoalStatus.PREEMPTING: (CommState.ACTIVE, CommState.PREEMPTING)},
233 GoalStatus.PENDING: NO_TRANSITION,
234 GoalStatus.ACTIVE: CommState.ACTIVE,
235 GoalStatus.REJECTED: CommState.WAITING_FOR_RESULT,
236 GoalStatus.RECALLING: CommState.RECALLING,
237 GoalStatus.RECALLED: (CommState.RECALLING, CommState.WAITING_FOR_RESULT),
238 GoalStatus.PREEMPTED: (CommState.ACTIVE, CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
239 GoalStatus.SUCCEEDED: (CommState.ACTIVE, CommState.WAITING_FOR_RESULT),
240 GoalStatus.ABORTED: (CommState.ACTIVE, CommState.WAITING_FOR_RESULT),
241 GoalStatus.PREEMPTING: (CommState.ACTIVE, CommState.PREEMPTING)},
243 GoalStatus.PENDING: INVALID_TRANSITION,
244 GoalStatus.ACTIVE: NO_TRANSITION,
245 GoalStatus.REJECTED: INVALID_TRANSITION,
246 GoalStatus.RECALLING: INVALID_TRANSITION,
247 GoalStatus.RECALLED: INVALID_TRANSITION,
248 GoalStatus.PREEMPTED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
249 GoalStatus.SUCCEEDED: CommState.WAITING_FOR_RESULT,
250 GoalStatus.ABORTED: CommState.WAITING_FOR_RESULT,
251 GoalStatus.PREEMPTING: CommState.PREEMPTING},
252 CommState.WAITING_FOR_RESULT: {
253 GoalStatus.PENDING: INVALID_TRANSITION,
254 GoalStatus.ACTIVE: NO_TRANSITION,
255 GoalStatus.REJECTED: NO_TRANSITION,
256 GoalStatus.RECALLING: INVALID_TRANSITION,
257 GoalStatus.RECALLED: NO_TRANSITION,
258 GoalStatus.PREEMPTED: NO_TRANSITION,
259 GoalStatus.SUCCEEDED: NO_TRANSITION,
260 GoalStatus.ABORTED: NO_TRANSITION,
261 GoalStatus.PREEMPTING: INVALID_TRANSITION},
262 CommState.WAITING_FOR_CANCEL_ACK: {
263 GoalStatus.PENDING: NO_TRANSITION,
264 GoalStatus.ACTIVE: NO_TRANSITION,
265 GoalStatus.REJECTED: CommState.WAITING_FOR_RESULT,
266 GoalStatus.RECALLING: CommState.RECALLING,
267 GoalStatus.RECALLED: (CommState.RECALLING, CommState.WAITING_FOR_RESULT),
268 GoalStatus.PREEMPTED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
269 GoalStatus.SUCCEEDED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
270 GoalStatus.ABORTED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
271 GoalStatus.PREEMPTING: CommState.PREEMPTING},
272 CommState.RECALLING: {
273 GoalStatus.PENDING: INVALID_TRANSITION,
274 GoalStatus.ACTIVE: INVALID_TRANSITION,
275 GoalStatus.REJECTED: CommState.WAITING_FOR_RESULT,
276 GoalStatus.RECALLING: NO_TRANSITION,
277 GoalStatus.RECALLED: CommState.WAITING_FOR_RESULT,
278 GoalStatus.PREEMPTED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
279 GoalStatus.SUCCEEDED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
280 GoalStatus.ABORTED: (CommState.PREEMPTING, CommState.WAITING_FOR_RESULT),
281 GoalStatus.PREEMPTING: CommState.PREEMPTING},
282 CommState.PREEMPTING: {
283 GoalStatus.PENDING: INVALID_TRANSITION,
284 GoalStatus.ACTIVE: INVALID_TRANSITION,
285 GoalStatus.REJECTED: INVALID_TRANSITION,
286 GoalStatus.RECALLING: INVALID_TRANSITION,
287 GoalStatus.RECALLED: INVALID_TRANSITION,
288 GoalStatus.PREEMPTED: CommState.WAITING_FOR_RESULT,
289 GoalStatus.SUCCEEDED: CommState.WAITING_FOR_RESULT,
290 GoalStatus.ABORTED: CommState.WAITING_FOR_RESULT,
291 GoalStatus.PREEMPTING: NO_TRANSITION},
293 GoalStatus.PENDING: INVALID_TRANSITION,
294 GoalStatus.ACTIVE: INVALID_TRANSITION,
295 GoalStatus.REJECTED: NO_TRANSITION,
296 GoalStatus.RECALLING: INVALID_TRANSITION,
297 GoalStatus.RECALLED: NO_TRANSITION,
298 GoalStatus.PREEMPTED: NO_TRANSITION,
299 GoalStatus.SUCCEEDED: NO_TRANSITION,
300 GoalStatus.ABORTED: NO_TRANSITION,
301 GoalStatus.PREEMPTING: INVALID_TRANSITION}}
305 def __init__(self, action_goal, transition_cb, feedback_cb, send_goal_fn, send_cancel_fn):
312 self.
state = CommState.WAITING_FOR_GOAL_ACK
318 return self.action_goal.goal_id.id == o.action_goal.goal_id.id
322 return hash(self.action_goal.goal_id.id)
325 rospy.logdebug(
"Transitioning CommState from %s to %s",
326 CommState.to_string(self.
state), CommState.to_string(state))
334 if self.
state == CommState.DONE:
341 if self.
state not in [CommState.WAITING_FOR_GOAL_ACK,
342 CommState.WAITING_FOR_RESULT,
350 if self.
state not in _transitions:
351 rospy.logerr(
"CommStateMachine is in a funny state: %i" % self.
state)
353 if status.status
not in _transitions[self.
state]:
354 rospy.logerr(
"Got an unknown status from the ActionServer: %i" % status.status)
356 next_state = _transitions[self.
state][status.status]
359 if next_state == NO_TRANSITION:
361 elif next_state == INVALID_TRANSITION:
362 rospy.logerr(
"Invalid goal status transition from %s to %s" %
363 (CommState.to_string(self.
state), GoalStatus.to_string(status.status)))
365 if hasattr(next_state,
'__getitem__'):
372 rospy.logdebug(
"Transitioning to %s (from %s, goal: %s)",
373 CommState.to_string(state), CommState.to_string(self.
state),
374 self.action_goal.goal_id.id)
380 self.latest_goal_status.status = GoalStatus.LOST
385 if self.action_goal.goal_id.id != action_result.status.goal_id.id:
392 if self.
state in [CommState.WAITING_FOR_GOAL_ACK,
393 CommState.WAITING_FOR_CANCEL_ACK,
396 CommState.WAITING_FOR_RESULT,
398 CommState.PREEMPTING]:
400 status_array = GoalStatusArray()
401 status_array.status_list.append(action_result.status)
405 elif self.
state == CommState.DONE:
406 rospy.logerr(
"Got a result when we were already in the DONE state")
408 rospy.logerr(
"In a funny state: %i" % self.
state)
412 if self.action_goal.goal_id.id != action_feedback.status.goal_id.id:
436 except AttributeError:
437 raise ActionException(
"Type is not an action spec: %s" % str(ActionSpec))
441 id, g_goal_id = g_goal_id, g_goal_id + 1
442 now = rospy.Time.now()
443 return GoalID(id=
"%s-%i-%.3f" % (rospy.get_caller_id(), id, now.to_sec()), stamp=now)
454 def init_goal(self, goal, transition_cb=None, feedback_cb=None):
455 action_goal = self.
ActionGoal(header=Header(),
458 action_goal.header.stamp = rospy.get_rostime()
464 self.statuses.append(weakref.ref(csm))
474 live_statuses = [r()
for r
in self.
statuses]
475 live_statuses = filter(
lambda x: x, live_statuses)
488 status.update_status(status_array)
492 status.update_result(action_result)
496 status.update_feedback(action_feedback)
518 except AttributeError:
519 raise ActionException(
"Type is not an action spec: %s" % str(ActionSpec))
528 self.manager.register_send_goal_fn(self.pub_goal.publish)
529 self.manager.register_cancel_fn(self.pub_cancel.publish)
552 def send_goal(self, goal, transition_cb=None, feedback_cb=None):
553 return self.manager.init_goal(goal, transition_cb, feedback_cb)
560 cancel_msg = GoalID(stamp=rospy.Time.from_sec(0.0), id=
"")
561 self.pub_cancel.publish(cancel_msg)
570 cancel_msg = GoalID(stamp=time, id=
"")
571 self.pub_cancel.publish(cancel_msg)
584 timeout_time = rospy.get_rostime() + timeout
585 while not rospy.is_shutdown():
587 server_id = self.last_status_msg._connection_header[
'callerid']
589 if self.pub_goal.impl.has_connection(server_id)
and \
590 self.pub_cancel.impl.has_connection(server_id):
595 for stat
in self.status_sub.impl.get_stats()[1]:
600 for stat
in self.result_sub.impl.get_stats()[1]:
604 feedback_num_pubs = 0
605 for stat
in self.feedback_sub.impl.get_stats()[1]:
607 feedback_num_pubs += 1
609 if status_num_pubs > 0
and result_num_pubs > 0
and feedback_num_pubs > 0:
613 if timeout != rospy.Duration(0.0)
and rospy.get_rostime() >= timeout_time:
622 self.manager.update_statuses(msg)
625 self.manager.update_results(msg)
628 self.manager.update_feedbacks(msg)
def __init__(self, action_goal, transition_cb, feedback_cb, send_goal_fn, send_cancel_fn)
def _status_cb(self, msg)
def set_state(self, state)
def update_feedback(self, action_feedback)
Client side handle to monitor goal progress.
def cancel_all_goals(self)
Cancels all goals currently running on the action server.
def cancel(self)
Sends a cancel message for this specific goal to the ActionServer.
def __init__(self, ActionSpec)
def send_goal(self, goal, transition_cb=None, feedback_cb=None)
Sends a goal to the action server.
def register_send_goal_fn(self, fn)
def wait_for_server(self, timeout=rospy.Duration(0.0))
Waits for the ActionServer to connect to this client.
def _find_status_by_goal_id(status_array, id)
def wait_for_action_server_to_start(self, timeout=rospy.Duration(0.0))
[Deprecated] Use wait_for_server
def init_goal(self, goal, transition_cb=None, feedback_cb=None)
Sends off a goal and starts tracking its status.
def get_goal_status_text(self)
Returns the current status text of the goal.
def __eq__(self, o)
True iff the two ClientGoalHandle's are tracking the same goal.
def update_results(self, action_result)
def cancel_goals_at_and_before_time(self, time)
Cancels all goals prior to a given timestamp.
def _result_cb(self, msg)
def register_cancel_fn(self, fn)
def get_name_of_constant(C, n)
def __init__(self, comm_state_machine)
Internal use only.
def update_feedbacks(self, action_feedback)
def get_goal_status(self)
Returns the current status of the goal.
def __ne__(self, o)
True iff the two ClientGoalHandle's are tracking different goals.
def get_terminal_state(self)
Gets the terminal state information for this goal.
def get_comm_state(self)
Get the state of this goal's communication state machine from interaction with the server...
def _get_live_statuses(self)
def get_result(self)
Gets the result produced by the action server for this goal.
def update_status(self, status_array)
def __init__(self, ns, ActionSpec)
Constructs an ActionClient and opens connections to an ActionServer.
def update_result(self, action_result)
def __hash__(self)
Hash function for CommStateMachine
def __hash__(self)
Hash function for ClientGoalHandle
def transition_to(self, state)
def _feedback_cb(self, msg)
def update_statuses(self, status_array)
Updates the statuses of all goals from the information in status_array.