Skip to content

Commit

Permalink
Command the robot to stop on canceling navigation
Browse files Browse the repository at this point in the history
  • Loading branch information
corot committed Oct 23, 2019
1 parent 7ed10b1 commit e4cdbb9
Showing 1 changed file with 1 addition and 0 deletions.
1 change: 1 addition & 0 deletions mbf_abstract_nav/src/abstract_controller_execution.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,6 +269,7 @@ namespace mbf_abstract_nav

if (cancel_)
{
publishZeroVelocity(); // command the robot to stop on canceling navigation
setState(CANCELED);
condition_.notify_all();
moving_ = false;
Expand Down

10 comments on commit e4cdbb9

@reinzor
Copy link
Contributor

@reinzor reinzor commented on e4cdbb9 Feb 13, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shouldn't we leave this the responsibility of the running plugin? We are using MoveBaseFlex in our robot but our robot does not have to stop when it receives a new plan from the planner. Now, the previous plan gets preempted and the robot continuous following the next plan. However, with this commit, a zero velocity is published in between. So it is braking the interface IMO. I don't think this should be in the "general navigation framework" but it should be implemented in the cancel hook of the controller (if desired). Related to #109 (same arguing).

@corot
Copy link
Collaborator Author

@corot corot commented on e4cdbb9 Feb 13, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

But there's something worng here: if you keep sending new plans to the robot without stopping the controller (that is, send new goals to exe_path while another is running), we adopt the new plan and continue the navigation uninterrupted, so no zero-velocity command should be send. Code here. This requires two conditions, though:

  • you don't change your concurrency slot (or let the default, that it's always 0)
  • you don't change your controller

How are you sending the new plans? Please double check that you are not cancelling exe_path and the calling it again with the new plan.

@reinzor
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That is indeed what we are doing. Just to be clear, who is calling the cancel method then? And when?

@corot
Copy link
Collaborator Author

@corot corot commented on e4cdbb9 Feb 13, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You mean this cancel? Is the exe_path action cancel callback. Do you print something to verify that it's getting called?

@reinzor
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So here? And this is only triggered when a user explicitly cancels the running goal. So the running goal on the same concurrency slot is not cancelled when a new goal is received (this would be the case with a default SimpleActionServer)? How does the user from the running goal get notified about the fact that the previous plan is not pursuit anymore?

@corot
Copy link
Collaborator Author

@corot corot commented on e4cdbb9 Feb 14, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No, that line is triggered when you send a new goal with different plugin or concurrency slot. Otherwise, you run this. We detect the fact that the new goal is to be executed with the same plugin and in the same concurrency slot, so we don't cancel the action in progress but just set a new plan. On the client side, you don't get any notification; just the second goal replaces the first one.

@reinzor
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, this clears things up! Thanks!

@corot
Copy link
Collaborator Author

@corot corot commented on e4cdbb9 Feb 14, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Cool!
Can I close the issue?

@reinzor
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This was more regarding this commit, there wasn't an issue attached :)

@corot
Copy link
Collaborator Author

@corot corot commented on e4cdbb9 Feb 14, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ah! true. Sorry. Anyway, we will put that zero-velocity command under a parameter, so users can disable it. See discussion on #171 for details

Please sign in to comment.