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

Tuning Navigation - robot keeps rotating when close to its goal

asked 2011-04-21 05:52:41 -0600

raphael favier gravatar image

updated 2011-04-26 11:08:56 -0600

Hello,

My robot Mojo and I are happily trying to use the navigation stack.

After a bit of parameter tuning, I managed to get it follow its planned path quite well.

My only problem is that things get pretty rotational when Mojo closes on its goal. As you can see in this video, it is like if it forgets it can also not move forward while rotating. Mojo is fitted with a differential drive.

I tried to play with some parameters of the base planner, but I can't really figure out how to stop this annoying rotation. This is not my first experience with the navigation stack and I know it is possible to reach the goal far better than that.

Has anyone ever experienced this behaviour? How could I make it stop?

Here are my base planner parameters:

TrajectoryPlannerROS:
  max_vel_x: 0.45
  min_vel_x: 0.1

  max_rotational_vel: 0.5
  min_in_place_rotational_vel: 0.1

  acc_lim_th: 0.25
  acc_lim_x: 0.5

  vx_samples: 5                       #default is 3, I feel like putting 5. I'm the architect after all! :)
  vtheta_samples: 20                  #default is 20

  holonomic_robot: false

  path_distance_bias: 5.0             #default .6
  goal_distance_bias: 0.8             #default .8
  occdist_scale: 0.01                 #default 0.01

  heading_lookahead: 0.325            #default 0.325m   
  heading_scoring: false              #default false
  heading_scoring_timestep: 5.0       #default 0.8 sec

  sim_time: 5.0                       #default is 1.0 - simulate 5 seconds ahead
  sim_granularity: 0.025              #default is 0.025 - simulation with steps of 2.5 cm

  dwa: false                          #I prefer trajectory rollout as I can see it in rviz

  xy_goal_tolerance: 0.2              #default is 10cm but I think AMCL makes it too giggly for this to be safe
  yaw_goal_tolerance: 0.09            #default is 0.05 rad (~3 degrees), I changed it to 5

Thanks in advance for your help

Raph

edit retag flag offensive close merge delete

4 Answers

Sort by ยป oldest newest most voted
27

answered 2011-04-26 08:00:49 -0600

eitan gravatar image

updated 2011-05-02 05:54:17 -0600

Note: As suggested, this guide has now moved to the ROS wiki. For an up-to-date version of the navigation tuning guide please see the Navigation Tuning Guide Tutorial.

Ok. First off, I'll answer the question about turning at a really low angular speed. This is just a bug which should be fixed in the next patch release of navigation. There's a ticket to track it here: https://kforge.ros.org/navigation/trac/ticket/2.

As for the broader question of how to tune the navigation stack, I'll do my best below to outline how I typically go about things. With that said, its a bit different for every robot. So, with no further ado, basic navigation tuning:

Basic Navigation Tuning Guide

This guide seeks to give some standard advice on how to tune the ROS Navigation Stack on a robot. This guide is in no way comprehensive, but should give some insight into the process. I'd also encourage folks to make sure they've read the ROS Navigation Tutorial before this post as it gives a good overview on setting the navigation stack up on a robot wheras this guide just gives advice on the process.

Step 1: Is the robot navigation ready?

The large majority of the problems I run into when tuning the navigation stack on a new robot lie in areas outside of tuning parameters on the local planner. Things are often wrong with the odometry of the robot, localization, sensors, and other pre-requisites for running navigation effectively. So, the first thing I do is to make sure that the robot itself is navigation ready. This consists of three component checks: range sensors, odometry, and localization.

Range Sensors

If the robot isn't getting information from its range sensors, such as lasers, then nothing with navigation will work. I'll make sure that I can view sensor information in rviz, that it looks relatively correct, and that its coming in at the expected rate.

Odometry

Often, I'll have a lot of trouble getting a robot to localize correctly. It will constantly get lost and I'll spend a lot of time mucking with the parameters for AMCL only to find that the real culprit is the robot's odometry. As such, I always run two sanity checks to make sure that I believe the odometry of a robot.

The first test checks how reasonable the odometry is for rotation. I open up rviz, set the frame to "odom," display the laser scan the robot provides, set the decay time on that topic high (something like 20 seconds), and perform an in-place rotation. Then, I look at how closely the scans match each other on subsequent rotations. Ideally, the scans will fall right on top of each other, but some rotational drift is expected, so I just make sure that the scans aren't off by more than a degree or two.

The next test is a sanity check on odometry for translation ... (more)

edit flag offensive delete link more

Comments

Regarding the "publish_cost_grid" parameter: Indeed it never did make it into the docs. Oops. For reference, the original ticket with info is here: https://code.ros.org/trac/ros-pkg/ticket/4620 . @eitan, do you know if the rviz patch (#4610) ever got released into the Debian builds?
Eric Perko gravatar image Eric Perko  ( 2011-04-26 08:25:03 -0600 )edit
Should this type of "howto" live on the ros.org wiki?
JeffRousseau gravatar image JeffRousseau  ( 2011-04-28 00:56:24 -0600 )edit
Eitan, thanks a lot for this guide. I would have one more interrogation though: Could you explain if the base controllers are strongly depending on accurate instantaneous speeds (twist part of twist messages)?
raphael favier gravatar image raphael favier  ( 2011-04-28 03:04:43 -0600 )edit

Hello, I know I'm 4 years late but I performed the in-place rotation test and my result is this: link text Is this good or bad? I don't think it's very good odometry. Any ideas?

RND gravatar image RND  ( 2015-05-28 07:57:36 -0600 )edit
9

answered 2011-04-21 06:09:06 -0600

eitan gravatar image

So, from the video, it looks like mojo never actually achieves its goal position to perform an in-place rotation. Likely this is because you've got the sim_time parameter set to 5 seconds with a minimum velocity of 0.1 meters/second. Trajectory rollout scores trajectories based on their endpoints which means that any trajectory with positive x velocity will move at least 0.5 meters forward. So, when the robot gets close to the goal, in-place rotations and trajectories that take long arcs towards the goal will score higher than the straight line path that goes too far past the goal. I'd suggest turning sim_time down to something like 1.0 or 1.5 seconds. Also, this will likely mean you can turn your path_distance_bias parameter down a bit and still get reasonable behavior. If you have the CPU, I might also up the vx_samples since you're using trajectory rollout rather than dwa and will benefit from additional sampling in the x velocity space, perhaps something in the 8-10 range. Hope this helps.

edit flag offensive delete link more

Comments

I think this is the correct answer.

Tixiao gravatar image Tixiao  ( 2017-05-09 19:42:15 -0600 )edit
0

answered 2011-04-22 23:49:54 -0600

raphael favier gravatar image

Eitan,

thanks a lot, I will check on this after this week end.

Does that mean that the simulation does not stop if it finds a trajectory reaching the goal in less time than the total simulation time? Is this the phenomenon you describe in the documentation as "endpoint scoring"? (section 7)

Raph

edit flag offensive delete link more

Comments

That's correct, the simulation always scores trajectories from their endpoint. It doesn't special case the situation where the robot is close to the goal.
eitan gravatar image eitan  ( 2011-04-25 04:51:25 -0600 )edit
0

answered 2011-04-26 02:10:15 -0600

raphael favier gravatar image

Eitan,

I followed your advises, but I feel I now need to retune my path scoring parameters. Indeed, the robot now gets sometimes stuck in the middle of his trip. I suspect the planner cannot decide between two possible paths.

I am also seeing a weird thing here: Sometimes, my robot gets very close to its goal and start turning at a very very low angular speed. Alhtought my min_in_place_rotational_vel parameter is set to 0.1, I can see with rxplot that the base receives an angular velocity command around 0.0125 rad.sec^-1. Any idea of where this could come from?

Finally, I would have a broader question: This is the third time for me to port navigation on a robot (2 differential and 1 holomnic drive). Although I am a big fan of the stack, I usually find myself endlessly trying parameter combinations until the robot suddenly behaves like I want. I read the ros documentation quite extensively, but I must say navigation stays a kind of greyish box which I have problems understanding all interaction/configuration nooks and crannies. Therefore, I was wondering if, given your experience and that navigation is mainly your baby, you would advise any particular kind of tuning process. Are there any parameters you would start setting first? any particular tuning or diagnosis trick?

thanks again for your help

Raph

edit flag offensive delete link more

Comments

Please do not post comments as answers in the question topic. Use the "comment" function in the board. Helps keep things tidy and neat. :)
Pablo Hevia-Koch gravatar image Pablo Hevia-Koch  ( 2011-05-11 06:40:49 -0600 )edit

Question Tools

10 followers

Stats

Asked: 2011-04-21 05:52:41 -0600

Seen: 13,020 times

Last updated: May 02 '11