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

move_base - moving backwards

asked 2012-01-10 19:33:35 -0600

Robotnik gravatar image

Is there a way to configure move_base to follow paths forward and backward?

I have been able to create paths composed of forward and backward segments with SBPL, but move_base tries always to complete the path rotating and moving forward.

Thanks,

Robert

edit retag flag offensive close merge delete

3 Answers

Sort by » oldest newest most voted
2

answered 2012-01-11 00:57:10 -0600

AHornung gravatar image

updated 2012-01-11 03:49:18 -0600

Have a look at pose_follower as local planner in move_base. It's not really documented and needs some parameter tuning, but it will follow your originally planned path very closely. I believe both DWA and Trajectory Rollout will try to optimize your path and avoid backwards motion.

edit flag offensive delete link more

Comments

Hi, thank you, I will test this right now. I have just realized that the path published by /move_base_node/SBPLLatticePlanner/plan is the sequence of poses, but without orientation information (just x,y fields are used), so it might be hard for the planner to decide where to move forward and backward...
Robotnik gravatar image Robotnik  ( 2012-01-11 01:49:58 -0600 )edit
1
Keep in mind that that topic is not where move_base get's its global plan from. If you look at the source (line 362ish of sbpl_lattice_planner.cpp) you'll see that it does set yaw angle for the plan move_base gets (following the BaseGlobalPlanner interface).
Eric Perko gravatar image Eric Perko  ( 2012-01-11 02:30:08 -0600 )edit
You are right, thanks.
Robotnik gravatar image Robotnik  ( 2012-01-11 03:00:47 -0600 )edit
0

answered 2020-06-26 12:28:06 -0600

Another option is the TEB local planner. I've had success using that to find trajectories that involve driving backwards for a bit using the configuration from their tutorial. If anything, using that configuration, it is a little too eager to drive backwards.

edit flag offensive delete link more
0

answered 2012-01-10 21:07:31 -0600

michikarg gravatar image

I think you should check the parameters of your local planner settings. The local planner is responsible for driving the robot to the waypoints given from the global planner (SBPL in your case). Are you using DWA or base_local_planner?

edit flag offensive delete link more

Comments

hmm i just had a look at the parameters of the local planners and i cannot find anything about backwards motion except for the escape velocity... so i´m not sure if you can do this with the existing local planners...
michikarg gravatar image michikarg  ( 2012-01-10 21:17:30 -0600 )edit
Thanks for the response and the testing. I tried with "dwa: true" and false of the base_local_planner but both generate only forward motion...
Robotnik gravatar image Robotnik  ( 2012-01-10 22:37:10 -0600 )edit

Question Tools

Stats

Asked: 2012-01-10 19:33:35 -0600

Seen: 3,909 times

Last updated: Jun 26 '20