7 @package manage_actionlib 8 This module provides utility methods for setting up actionlib calls through an overarching actionlib server. 15 action_name=
"current action",
16 time_limit=float(
"inf"),
18 """Send and monitor an action goal to a given action client. 20 The monitor will return in case of the client reporting success, preemption or 21 abortion, and will also pass through any incoming preemptions to the action server. 23 @param action_server Action server that is calling the action client. If the action server is preempted, this is passed to the action client. 24 @param action_client The action client that is called by the action server. If the action server is preempted, the goal sent to this client is preempted as well. 25 @param action_goal The action goal to be sent to the action client. 26 @param action_name Optional name for the action. Will be displayed in the logs. 27 @param time_limit An optional time limit for the action. If exceeded, the action client is preempted 31 rospy.loginfo(
"Sending goal to " + action_name)
32 action_client.send_goal(action_goal)
33 init_time = rospy.Time.now()
34 while action_server.is_active():
35 if (rospy.Time.now() - init_time).to_sec() > time_limit:
36 rospy.logwarn(
"Timeout of request")
37 action_client.cancel_goal()
41 if action_server.is_preempt_requested():
42 rospy.logwarn(
"Preempting " + action_name)
43 action_client.cancel_goal()
44 finished = action_client.wait_for_result(
45 timeout=rospy.Duration(1.0))
48 rospy.logerr(action_name +
49 " failed to preempt! This should never happen")
50 action_server.set_aborted(text=
"Aborted due to action " +
51 action_name +
" failing to preempt")
53 action_server.set_preempted(
54 text=
"Preempted while running " + action_name)
55 rospy.loginfo(
"Preempted while running")
58 if action_client.get_state() == actionlib.GoalStatus.ABORTED:
59 rospy.logerr(action_name +
" aborted!")
62 action_server.set_aborted(text=action_name +
" aborted")
65 if action_client.get_state() == actionlib.GoalStatus.PREEMPTED:
66 rospy.logerr(action_name +
" preempted!")
69 action_server.set_aborted(text=action_name +
" was preempted")
72 if action_client.get_state() == actionlib.GoalStatus.SUCCEEDED:
73 rospy.loginfo(action_name +
" succeeded!")