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

move_base/base_local_planner maximum velocity

asked 2011-11-23 02:59:09 -0600

DimitriProsser gravatar image

I'm currently working on a large outdoor robot that requires high speeds to operate effectively. As such, I've tried to increase the command velocity output by move_base and base_local_planner, but upon increasing the max_vel_x parameter, I see a cap in the cmd_vel message output by move_base. My current configuration can be found here.

I have the max_vel_x parameter set to 10.0 m/s, but the maximum cmd_vel output by move_base is ~2.75m/s. I've observed this both in a simulated environment and on the actual robot.

I assumed that the forward simulation time might have something to do with it. I figured, "if the robot can't simulate far enough into the future, it may not allow itself to move faster than it can predict." I tested this theory by setting the sim_time parameter from 1.7 to 3.0. What I noticed was the exact opposite of what I predicted. With a higher sim_time, the maximum output cmd_vel was ~1.8m/s (lower than the previous). A sim_time of 5.0 resulted in a maximum cmd_vel of ~1m/s.

My question is: what are the factors that play into the calculation of the cmd_vel message output by base_local_planner, and is there any way to make it move faster? We're looking to achieve ~10m/s.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
9

answered 2011-12-01 05:29:24 -0600

eitan gravatar image

OK, I finally took some time to check this out. After playing around a bit I was able to get a robot, in an empty environment in simulation, to achieve very, very, high velocities. I'm not sure that the navigation stack is an awesome way to control an outdoor robot at high speeds, but I can at least give an explanation of why you were likely having trouble:

The local planner doesn't consume the entire global path for planning, instead it is given a region of the path that fits inside of a local window that based on the size of the local costmap. By default, the local costmap is centered at the robot and sized at 6m x 6m. This means that the goal point for the local planner is never going to be more about 3 meters away from the robot. As such, the cost function will actually limit the speeds the robot chooses to be slower because its planning to a point that is only a couple of meters away. Furthermore, as you increase the maximum velocity for the local planner, you're also increasing the size of the steps between simulated velocities. For example, 10 steps between 0 and 1 m/s would give 0.1 m/s increments, but 10 steps between 0 and 10 m/s would give 1.0m/s increments. As such, you could end up with slower velocities chosen for the 10 m/s max than the 1 m/s max because its at a coarser resolution. One solution here would bet to increase vx_samples, but this has performance implications as the planner will simulate a lot more trajectories.

I ended up changing my local map size to something absurdly large, it should be noted that this will also have some performance implications, and ran the local planner again with a high velocity limit. Lo and behold, the robot achieved its max velocity. To hit max velocity even faster, I upped the acceleration limits a bit, reduced the pdist_scale parameter to zero to allow the robot to just pursue its goal point, and switched to Trajectory Rollout from DWA since it consideres accelerations over the entire sim_time for the velocities it commands as opposed to DWA which just considers acceleration over the first simulation step.

I'm not sure this will make for the most reliable or robust planner for your application, but at least it explains what was happenning and I hope it helps.

edit flag offensive delete link more
1

answered 2011-11-23 03:17:43 -0600

eitan gravatar image

The base_local_planner computes the maximum velocity for a given time step as:

For DWA:
max_vel_x_iteration = min(max_user_vel_x, current_vx_from_odom + acc_limit_x * sim_period)

and

For Trajectory Rollout:
max_vel_x_iteration = min(max_user_vel_x, current_vx_from_odom + acc_limit_x * sim_time) for

As such, there shouldn't be a limit on the maximum velocity the base can achieve. Also, if you were running the planner in an environment that has obstacles, the longer sim time could result in more trajectories being in collision, especially those simulated with higher velocities. The base_local_planner is, admittedly, a bit simplistic in how it decides whether a trajectory is valid. It just checks if it collides with an obstacle at any point... even if that point is far enough away for the robot to stop before the collision. A couple of questions:

1) Have you tried running your test in an environment without obstacles? That should, for testing purposes, eliminate the worry that some trajectories are being detected as in-collision.

2) Are you sure that the planner is receiving odometry information from your base and that this information is correct? This could be another reason that the base doesn't achieve max velocity as it takes the current velocity of the robot and acceleration limits into account.

edit flag offensive delete link more

Comments

The environment is completely clear of obstacles. Also, the odometry topic that move_base is looking at is receiving the proper twist messages. This twist is calculated based on the rotation of the wheels and is fairly accurate in real-world application.
DimitriProsser gravatar image DimitriProsser  ( 2011-11-23 03:45:26 -0600 )edit
What I don't understand is the fact that it moves slower when I increase sim_time, and accel_limit_x seems to have no effect. Based on the above equation, this doesn't make much sense.
DimitriProsser gravatar image DimitriProsser  ( 2011-11-23 03:46:33 -0600 )edit
I even tried running this test in Gazebo, using base_pose_ground_truth for the most accurate odometry possible.
DimitriProsser gravatar image DimitriProsser  ( 2011-11-23 03:49:03 -0600 )edit
Hmmm... that is indeed strange, especially since I really did just go into the code for the equation. I'll try to take a look at things in more detail, run some tests of my own, and get back to you. It might take until Monday though because I've got a plane to catch for Thanksgiving weekend.
eitan gravatar image eitan  ( 2011-11-23 04:07:19 -0600 )edit

Question Tools

5 followers

Stats

Asked: 2011-11-23 02:59:09 -0600

Seen: 6,587 times

Last updated: Dec 01 '11