ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Cancelling a ROS action within an executive_teer node

asked 2013-04-04 04:58:28 -0600

Pi Robot gravatar image

updated 2013-04-04 04:58:49 -0600

Hello,

I am trying out the executive_teer package and my test setup is a simulated TurtleBot running two main tasks: a navigation task that moves the TurtleBot through a series of waypoints in a map using MoveBase actions and a battery_check task that monitors a simulated battery level and sends the robot to a charging base (also using MoveBase) when the level falls too low.

The trouble I am having is interrupting the current MoveBaseAction from the battery_check task when the battery level falls below threshold and while the robot is still on the way to a waypoint. Even though I send a move_base.cancel_goal() from the battery_check task, the robot always continues to the current waypoint before then heading to the charging station. I've also tried killing or pausing the navigation task but I get the same result--the MoveBaseAction appears to be outside the teer environment's control.

I can post the code details if necessary but perhaps there is some general trick when using teer with standard ROS actions?

Thanks!
patrick

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
0

answered 2013-04-07 23:40:37 -0600

The answer given by Patrick works, but misses the point of teer. A better solution would be to have self.move_base_done as a ConditionVariable, so that the co-routine is automatically un-paused when this variable becomes true. Please see this tutorial page for more informations about condition variables.

edit flag offensive delete link more

Comments

Thanks for the clarification @Stéphane Magnenat.

Pi Robot gravatar image Pi Robot  ( 2013-04-08 02:47:40 -0600 )edit
0

answered 2013-04-05 08:53:38 -0600

Pi Robot gravatar image

I figured out an answer to my own question. It appears that using the move_base wait_for_result() function is what is blocking teer from cancelling a current goal. But it turns out that you can override the move_base callbacks for "done", "feedback" and "active". So I now call move_base.send_goal() like this:

self.move_base_done = False
self.move_base.send_goal(self.goal, done_cb=self.move_base_done_cb)
while not self.move_base_done:
    yield WaitDuration(0.5)

where the self.move_base_cb callback is defined as:

def move_base_done_cb(self, status, result):
    self.move_base_done = True

And this now allows me to cancel a current goal from another teer task.

--patrick

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2013-04-04 04:58:28 -0600

Seen: 254 times

Last updated: Apr 07 '13