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

base_local_planner generates rotations away from global path

asked 2011-05-28 09:05:28 -0600

William gravatar image

updated 2011-05-29 14:03:02 -0600

Eric Perko gravatar image

We are trying to use the built in base_local_planner (blp) in move_base for our lawnmower. We have managed to get decent results with the current configuration even though we have some tf/timing issues that we are investigating.

However, I think another problem we are having is that the blp is giving us weird local paths. Visualizing the local paths in rviz (with the trunk rviz for visualizing the path cost as a pointcloud2), the local path is updating quickly and several of the paths will be inline with what we would expect (converging to the global path), but often there will be curved paths that curve away from the global path into the higher cost areas of the map. The robot will jerk in that direction, but it never stays committed to any one path for very long. This is the visual behavior that we have observed with the local path, the end result is that the robot jerks along because a fluid continuous local path is never allowed to play out.

Additionally, we get this behavior where the robot is near the path and facing the right direction (the obvious desired behavior is just to drive straight) and the robot will instead make a 360~ degree turn in the opposite direction of the path, i.e. if the path is like 5-10 cm to the right of the robot and the robot is parallel to the path in the correct direction it will make a complete turn to the left. We aren't sure what this behavior is about, but any insight into the inner workings that could cause this would be awesome.

I think we may have some odd configuration mishap that has result in "local path thrashing", currently we are running with the global costmap and the local costmap in the same frame with an empty map and no localization. You can see our up-to-date configurations here:

Our move_base Configuration Files

Our move_base Launch File

I can try to get a video of this behavior in rviz on youtube tonight, but we have spotty internet out here.

edit retag flag offensive close merge delete

Comments

Can you reproduce this behavior in simulation with, say Stage?
Eric Perko gravatar image Eric Perko  ( 2011-05-29 14:05:39 -0600 )edit

2 Answers

Sort by ยป oldest newest most voted
2

answered 2011-05-29 14:34:29 -0600

Eric Perko gravatar image

So, I've got a few thoughts on this:

  1. Have you seen the discussion about the navigation stack and nonholonomic robots? You can find it in the ros-users archive. If you read through it far enough, you'll get to some discussion about the spin-in-place scoring - basically the base_local_planner isn't the best at it so it does sometimes choose poor rotations. I don't know if this was ever solved, perhaps in the dwa_local_planner available in navigation_experimental.
  2. Have you tried to visualize the potential fields that you are creating with your scoring parameters? See ticket #4620 for some examples. I believe that functionality is in the released version of base_local_planner, but you'll have to check out visualization trunk in order to get a version of rviz that has had the patch from ticket #4610 applied. Basically, use this as a sanity check to make sure that the final combination actually keeps the trajectories out of the "high cost" areas of the map.
  3. Eitan wrote up a nice basic navigation stack tuning guide a bit ago. Have you guys looked through those hints?
  4. Not sure if it would help you, but you can find the navigation stack settings we used last year at IGVC 2010 in the cwru-ros-pkg (pick the version of any file with "outdoors" in the name if there is a version with and without that in the name). Those were working reasonably well for us at IGVC until our motor controller blew a FET and we had to switch to one that could only do about half the current we needed :(. We didn't really have any issues with moving into "high cost" areas of the map or spinning 360 degrees when we were almost on the path and still had a good deal left to go. The only time it did a poor spin in place was at goal points, start points or any other place where the path made sense to include a spin-in-place.

Hope something in there helps you guys out.

edit flag offensive delete link more

Comments

Thanks for answering eric, we really appreciate your input, let me reply in order: First, I looked at that mailing list thread a while ago, and we are currently trying stuff from the navigation experimental department like pose follower and such. Second, we are using your patched rviz and the costs
William gravatar image William  ( 2011-05-30 01:58:16 -0600 )edit
make sense to us. Third, we started out by doing the navigation tutorial and then running through Eitan's guide, it was helpful, but this problem persisted. Finally, we have looked at your configurations as well, and ours are pretty close, we'll just have to deal with the odd turns some other way.
William gravatar image William  ( 2011-05-30 02:02:01 -0600 )edit
0

answered 2011-05-31 05:12:59 -0600

eitan gravatar image

I'm not sure what changes you've made to your configuration after looking at Eric's, but the files you posted have a very small number of theta samples for simulating. Have you tried bumping up vtheta_samples to something like 20 from 5? Also, with your path_distance_bias set so low, the robot won't have much incentive to stay on the planned path, it'll just try to drive towards its local goal. This may be what you want, but its something to be aware of.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2011-05-28 09:05:28 -0600

Seen: 2,776 times

Last updated: May 31 '11