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

Limit rotation speed/acc in Navigation/base_local_planner

asked 2012-05-20 05:09:20 -0600

fherrero gravatar image

updated 2012-05-23 22:00:40 -0600

We are trying to use the navigation stack on a segway_rmp200. Currently we have configurated everything as said in this tutorial, we are not using a map yet, and we are sending a goal through rviz which can be reached going in a straight way (no obstacles between the robot and the goal).

Then, the segway starts doing weird translations and rotations, leaving the desired path, rotating, returning to the path, etc. Although it finally reaches the goal, the way it has moved is very weird. This is our first problem, and may result in a new question if the second problem is solved.

The second problem is that all these rotations are done with too high speed/acceleration and abrupt changes of direction, making it dangerous and not desirable to continue doing tests/debug to solve the first problem.

The parameters of the base_local_planner_params.yaml related to velocity and acceleration are set with low values (which seem to be ignored):

TrajectoryPlannerROS:    
  max_vel_x: 0.5    
  min_vel_x: 0.1    
  max_rotational_vel: 0.2    
  min_in_place_rotational_vel: 0.1    
  acc_lim_th: 0.05    
  acc_lim_x: 0.1    
  acc_lim_y: 0.1    
  holonomic_robot: false

In addition, running the dynamic reconfigure there are other similar parameters with different names as: max_vel_theta, min_vel_theta, min_in_place_vel_theta, acc_lim_theta; which have default higher values than the previous ones. We have modified them, but nothing has changed.

  1. Why is the rotation speed/acc not being limited with the configuration parameters?
  2. Why are there different parameter names (config yaml vs dynamic reconfigure) and which of them are the correct ones to tune? (3. Maybe related to 1, if not, future question: Why is our platform moving so weird to reach easy goals? How can we debug this behavior/state to see what is happening?)

Edited (after KruseT answer)

Now we are sure using the trajectory planner (dwa:false in base_local_planner_params.yaml), and can see the same values for yaml and dynamic-reconfigure parameters.

The problem continues. We set max_vel_th: 0.2 and acc_lim_th: 0.05, and the robot performs faster rotations. For example, the platform has received this two consecutive commands, where those limits have not been respected, and this is happening most of the time:

New Command Received: vT=0.100000 vR=0.000000
New Command Received: vT=0.117907 vR=1.371679

Translations are working fine. We have disabled recovery_behaviors, but there are no obstacles in the way so they shouldn't be used. We don't know how to continue debugging this to find out what's happening.

Any ideas?

edit retag flag offensive close merge delete

Comments

Have you resolved this issue? I am having the exact same problem. Even if I command the robot to drive to a goal directly in front of it, it starts turning and (eventually)...gets to the goal after following a convoluted path.

mkoval gravatar image mkoval  ( 2012-05-27 13:24:01 -0600 )edit

We haven't resolved it yet. Now it's not our first priority issue, but we'll get back into it soon. We will try to do some debug and we also found some messages "Control loop missed its desired rate of 20.0000Hz..." so we will try decreasing the controller frequency.

fherrero gravatar image fherrero  ( 2012-05-28 21:40:20 -0600 )edit

If it's any help, I found that my problem was actually caused by latency in our localization algorithm's orientation estimate. Our global planner uses a fixed frame of /map and the local planner uses /odom, so bad (i.e. laggy) transformation from /map -> /odom was causing all of the issues.

mkoval gravatar image mkoval  ( 2012-06-01 14:01:36 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
6

answered 2012-05-21 05:11:49 -0600

KruseT gravatar image

updated 2012-05-23 22:37:08 -0600

There are 2 main different localplanners in the ROS navigation stack, called trajectory_planner_ros and dwa_local_planner. Make sure to know which one you are using.

A parameter like acc_lim_x will be used for projecting trajectories in the future. Given acc_lim_th: 0.05, one such trajectory would e.g. have these velocities in its points: 0, 0.05, 0.10, 0.15, 0.20 (if the time between points were 1s, I use this just for keeping the numbers simple) So the acceleration limit between two points are respected. However (and I personally consider this a design flaw), what is used as a drive command then is the final velocity of that trajectory, 0.20. The rationale is that lower level components (or hardware) will cap the velocities to what the robot can/should maximally do.

The parameter names should be the same in config yaml and dynamic reconfigure. However, the parameter names differ between trajectory_planner_ros and dwa_local_planner (Also a design flaw, for historic reasons). So if you observe different parameter names in dynamic reconfigure, maybe you are using dwa_local_planner.

rotation speed/acc should be configurable with the parameters as 'theta' values.

Also consider this page for help: http://www.ros.org/wiki/navigation/Tutorials/Navigation%20Tuning%20Guide

[Edit after question has be extended:]

To check what local planner you are using, you can check at runtime using

$ rosparam get base_local_planner

The value may set in one of your launch files, with an entry like this:

<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />

With no such entry, move_base will by default use the trajectory_planner_ros. The dwa parameter you use is different, it allows to run trajectory_planner_ros to run similar to somewhat similar, but not the same, as dwa_planner_ros.

To debug you can display the costmap, local and global plan in rviz, see: http://www.ros.org/wiki/navigation/Tutorials/Using%20rviz%20with%20the%20Navigation%20Stack

Else to debug you'd have to add logging statements to trajectory_planner.cpp, in particular in createTrajectories, findBestPath and generate trajectory. This requires you to install the navigation stack from source.

In findBestPath you should find lines like:

tf::Vector3 start(best.xv_, best.yv_, 0);
drive_velocities.setOrigin(start);
tf::Matrix3x3 matrix;
matrix.setRotation(tf::createQuaternionFromYaw(best.thetav_));

This is where you can change the values by hand.

However, the dwa_planner_ros code is cleaner and should be easier to work with than the trajectory_planner_ros code.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2012-05-20 05:09:20 -0600

Seen: 3,205 times

Last updated: May 23 '12