32 from actionlib_msgs.msg
import GoalStatus
42 SimpleGoalState.to_string = classmethod(get_name_of_constant)
82 def send_goal(self, goal, done_cb=None, active_cb=None, feedback_cb=None):
108 def send_goal_and_wait(self, goal, execute_timeout=rospy.Duration(), preempt_timeout=rospy.Duration()):
112 rospy.logdebug(
"Canceling goal")
115 rospy.logdebug(
"Preempt finished within specified preempt_timeout [%.2f]", preempt_timeout.to_sec())
117 rospy.logdebug(
"Preempt didn't finish specified preempt_timeout [%.2f]", preempt_timeout.to_sec())
125 rospy.logerr(
"Called wait_for_result when no goal exists")
128 timeout_time = rospy.get_rostime() + timeout
129 loop_period = rospy.Duration(0.1)
131 while not rospy.is_shutdown():
132 time_left = timeout_time - rospy.get_rostime()
133 if timeout > rospy.Duration(0.0)
and time_left <= rospy.Duration(0.0):
139 if time_left > loop_period
or timeout == rospy.Duration():
140 time_left = loop_period
149 rospy.logerr(
"Called get_result when no goal is running")
163 return GoalStatus.LOST
164 status = self.
gh.get_goal_status()
166 if status == GoalStatus.RECALLING:
167 status = GoalStatus.PENDING
168 elif status == GoalStatus.PREEMPTING:
169 status = GoalStatus.ACTIVE
181 rospy.logerr(
"Called get_goal_status_text when no goal is running")
182 return "ERROR: Called get_goal_status_text when no goal is running"
216 rospy.logerr(
"Got a transition callback on a goal handle that we're not tracking")
219 comm_state = gh.get_comm_state()
221 error_msg =
"Received comm state %s when in simple state %s with SimpleActionClient in NS %s" % \
222 (CommState.to_string(comm_state), SimpleGoalState.to_string(self.
simple_state), rospy.resolve_name(self.
action_client.ns))
224 if comm_state == CommState.ACTIVE:
230 rospy.logerr(error_msg)
231 elif comm_state == CommState.RECALLING:
233 rospy.logerr(error_msg)
234 elif comm_state == CommState.PREEMPTING:
240 rospy.logerr(error_msg)
241 elif comm_state == CommState.DONE:
242 if self.
simple_state in [SimpleGoalState.PENDING, SimpleGoalState.ACTIVE]:
244 self.
done_cb(gh.get_goal_status(), gh.get_result())
249 rospy.logerr(
"SimpleActionClient received DONE twice")
258 rospy.logerr(
"Got a feedback callback on a goal handle that we're not tracking. %s vs %s" %
259 (self.
gh.comm_state_machine.action_goal.goal_id.id, gh.comm_state_machine.action_goal.goal_id.id))