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

Move_base/dwa parameters for a large robot with rotation center in the front

asked 2015-01-22 11:32:17 -0600

Amir Shantia gravatar image

updated 2015-01-27 03:11:10 -0600

Edit 1: Video Link to Trial 1- link text

Edit 2: Video Link to Trial N - Working but not perfect system: here

Dear Navigation experts and other respective ROS users,

I have been struggling with an annoying problem for a while which I hope you can help me to solve it.

Robot properties:

I have a robot with the following size: 70x60x50(L,W,H). (Volksbot RT3 differential drive, modified and bigger). This robot has two maxon 150w engines, and two maxon controllers with 74:1 gears.

The rotation centre of the robot is on the front axis of the robot, and therefore I have the base_link and base_footprint on that point. This point is 12cm behind from the front of the robot.

We use ROS Hydro, Ubuntu 12.04

Sensors:

Laser: in the front

  • Front_rotating_xtion -> down sampled to leaf size of 5cm

  • Back_fixed_xtion -> down sampled to leaf size of 5cm

  • I use multiple obstacle layers so the sensors do not overwrite each other

Note: We started using xtions/kinect since Fuerte, and we always had to make two observation sources for one camera, and set one for marking and the other for clearing. Otherwise it wouldn't work. (Perhaps it changed but we didn't try)

Problem

When I give a navigation goal, the global plan is somewhat reasonable. I intentionally increased the inflation radius in the global costmap to avoid having tricky situation. My problem is that the dwa local planner puts the robot in very a difficult situations, and the robot gets stuck easily while there is a clear solution to the movement problem. Instead of following the path, it likes to stick to obstacles, and get itself stuck. When stuck, it keeps oscillating instead of move in reverse and correct its path. I do not penalize negative_x movement because the robot can see its behind pretty good. I read all the documentations for all sections of move_base. I changed a lot of variables to see the effect, but none of them really satisfied me, because the robot gets stuck so easily, and it doesn't get out of it.

Below the text are my move_base parameter files (Hopefully it can be also used as a reference for people who are trying to get hydro style move_Base to work with multiple sensors):

The things I have tried:

For DWA robot configuration parameters, I checked the plotted cmd_vel versus the odometry reading. The perfect plot match was with the given parameters below. (I used rqt_plot)

  • I fiddled around with all the Forward simulation parameters, and the trajectory scoring parameters.
  • I increased/decreased the inflation radius for both local and global costmap, and increase/decreased their resolution.
  • I tried changing the reference frame to the centre of the robot instead of centre of rotation.
  • I fiddled around with controller_frequency and planner and controller patience.
  • I checked whether the TF matches the robot (with xtions veiwing the robot)

  • I will prepare a video link and add it here so you ...

(more)
edit retag flag offensive close merge delete

Comments

1

Can you specify a little more what you mean by "stick to obstacles"? Uploading diagrams would be helpful. (If you can't upload pictures, email me the pictures and I'll edit the question for you).

David Lu gravatar image David Lu  ( 2015-01-24 14:33:42 -0600 )edit

Thank you for responding David. I will take some detailed pictures and videos and will email them tomorrow the latest.

Amir Shantia gravatar image Amir Shantia  ( 2015-01-25 08:51:11 -0600 )edit

I updated the link, and sent some pictures for you to add to the topic.

Amir Shantia gravatar image Amir Shantia  ( 2015-01-26 08:25:19 -0600 )edit

2 Answers

Sort by ยป oldest newest most voted
5

answered 2015-01-26 12:05:51 -0600

Amir Shantia gravatar image

updated 2015-01-28 03:00:12 -0600

Based on @DavidLu's answers I started the following trials:

  1. I corrected to the footprint to match the robot as much as possible. It didn't improved very much.
  2. I also found out that my robot was not rotating/moving properly, and I fixed it as well. It improved the localization and movement, but the problem was still there.
  3. I did fiddle around with inflation radius, it improved the movement. However, the robot could still get stuck frequently, or as you saw in the first video link, it was moving slow.
  4. Then I thought well, I am going to read the source code, which helped a lot. and thanks for good coding + comments. In dwa_local_planner page, the forward_point_distance is defined as an additional scoring point in front of the robot. I frankly didn't understand what it meant. However, in the source code, I found out that this value is being used as a cost value for robot alignment to the path. By setting it to zero, the trajectory will not be penalized if the robot is not aligned on the path. This is a very important factor for differential drive robots whose centre of rotation is not the in the middle of the robot. Apparently, a lot of valid trajectories were being dropped because of this. As soon as I set this to zero, the robot was able to perform much better. However, improvements could be done so I continued.
  5. I found a very interesting debugging feature in the planner which helps in visualizing the simulated trajectory points. There is a publish_traj_pc private node handler parameter value which is false by default. I didn't know how to set it to true from the config files, so I enabled it in the source and recompiled. The only downside was that the trajectory centres was not on the robot (perhaps their base frame was base_footprint or base_link while I was using map as the reference frame). However, if you select odom as the reference frame in the local costmap parameters, the trajectories will be on the robot.
  6. Using the new visualization parameter, I played around with sim_time, trajectory scoring parameters, vx_samples, and vtheta_samples (note that vy_sample should be 0 or 1 cause the robot does not move in Y vector space). When the number of samples are high, there is higher chance to find solutions if the robot is in a tricky situation. However, increasing the samples requires extensive calculations and after a point move_base will thell you that desired control frequency cannot be achieved. By increasing sim_period the simulation takes longer, and may help in better solutions, but the downside is not achieving the desired control frequency.

I uploaded another video on youtube with the latest knowledge: Trial N, success

After a lot of trials, I can conclude that one set of parameters is not enough for a reliable navigation. I would recommend having a couple of settings for different environmental situations. And change the parameters using dynamic reconfigure ... (more)

edit flag offensive delete link more

Comments

Glad to hear it. Can we close this question?

David Lu gravatar image David Lu  ( 2015-01-27 11:08:55 -0600 )edit

Yes, of course. I was waiting for enough karma to be able to select the answer. Thanks again for the guidance.

Amir Shantia gravatar image Amir Shantia  ( 2015-01-28 02:58:30 -0600 )edit
3

answered 2015-01-24 14:29:36 -0600

David Lu gravatar image

updated 2015-01-26 10:10:55 -0600

How does the dwa_local_planner know about the rotation axis length of the robot? Is it from the footprint?

DWA does not explicitly model the rotation axis length. It assumes the rotation happens relative to /base_footprint and uses the footprint to figure out how much space the robot takes up.

My footprint is a simplified almost rectangular bounding box of the robot. Does it make a difference If I make it precise enough to exactly match the footprint of the robot?

It's not likely that the precision will make a difference unless the footprint is a bad approximation.

Is the Cost value example in the dwa_local_planner webpage that is calculated from the goal_distance , path_distance and occdist values a positive (the high the better path) or negative value? On top of the page it talks about a scoring trajectory but below the example is cost, so I am a bit confused.

Yes, the language is not clear. It is calculated in terms of costs, not positive scores. It minimizes the sum of the costs.

Do you know why the robot fails while there is a clear solution available?

One bit is that your inflation radius is too small. It should be at least half the width of your robot (.28)

edit flag offensive delete link more

Question Tools

6 followers

Stats

Asked: 2015-01-22 11:32:17 -0600

Seen: 5,979 times

Last updated: Jan 28 '15