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

What is the difference between min_vel_x, min_trans_vel and trans_stopped_vel?

asked 2020-07-10 02:19:31 -0500

parzival gravatar image

This might be a stupid question, but in the DWA planner, I've seen group of these three parameters which seems to be indicating the same thing to me.

My understanding: Minimum velocity in x direction is 0.1m/s let's say. Then by definition, that is also going to be the minimum translational velocity. For trans_stopped_vel, when I hover over the parameter in rqt_reconfigure, I see the definition on the lines of "Minimum velocity below which the robot is assumed to be not translating", which again seems to be saying the same thing to me.

If these three parameters actually mean the same thing, then it would be a waste to set them in thrice, so I'm assuming that there is a good reason they are not the same. Please enlighten me if that is the case and explain what each of them does.

Secondly, if I want the robot to be moving forward when possible and back off when it can't move forward but not prefer moving backwards otherwise, what values should I set these three parameters to?

Related third question: Is min_in_place_vel_theta parameter supported in kinetic and higher? I've seen some people mention it in previous answers, but I haven't noticed any difference by including/excluding it. And again, how are min_in_place_vel_theta, rot_stopped_vel and min_rot_vel different?

This group of parameters which seems trivially different to me appears for minimum rotational velocity, max velocities as well.

I'm happy to read the paper on DWA if it needs more information to understand, and would be happy if someone can point me to some literature for in depth understand, but I also think it would be beneficial for me and others to know at least a short summary to get it working with the DWA algorithm still being abstract, because I think that's the true advantage of ROS.

Robot details: I have a non-holonomic two wheeled differential drive robot, with DC geared motors(175rpm, 8.4kgfcm)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2020-07-10 09:30:30 -0500

David Lu gravatar image

One key thing to remember is that some robots (notably the PR2) can move in both x and y directions, so many of the parameters allow for translation in both x and y. Your robot can only move in x.

min_vel_x is the minimum value the robot will generate in the x direction.. If the value is negative, then the robot could drive backwards.

If you have a holonomic robot, that value may be 0.0 to allowed to be 0 to allow for pure translation in the Y direction. However, if you allow for both the x velocity and y velocity to be zero, it may choose a velocity of 0 in BOTH directions. That is often times unproductive, so you want to make sure its translating in some direction. That is what min_trans_vel is for. However, with non-holonomic robots, it doesn't make much difference.

min_rot_vel serves the same general function, but there's only one way to turn.

trans_stopped_vel is only used at the end of your navigation when the robot is stopping. At this point, you do want to command your robot at a speed less than your min_vel_x. trans_stopped_vel is the velocity at which we consider the robot to be "stopped" , and when it is stopped, then we can mark the goal as succeeded. Similarly rot_stopped_vel

There exists code to have your robot prefer to move forward, but its not actually used anywhere IIRC.

I don't believe min_in_place_vel_theta is used by DWA.

There may be additional ros2 related answers here

edit flag offensive delete link more

Comments

@David_Lu Great post. For understanding, min_rot_vel with a non zero value will make the robot always cmd_vel z theta >0 then, will never drive in a straight line? min_trans_vel would forbid an in place rotation? Would really appreciate an answer as the dwa parameters seemt to be a bit of an enigma.

Dragonslayer gravatar image Dragonslayer  ( 2020-07-10 10:34:47 -0500 )edit

This answered all my questions, thanks a lot David!

parzival gravatar image parzival  ( 2020-07-14 08:22:42 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-07-10 02:19:31 -0500

Seen: 1,234 times

Last updated: Jul 10 '20