Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

try base_local_planner instead of dwa_local_planner #40

Open
marc-hanheide opened this issue Mar 3, 2015 · 17 comments
Open

try base_local_planner instead of dwa_local_planner #40

marc-hanheide opened this issue Mar 3, 2015 · 17 comments
Assignees

Comments

@marc-hanheide
Copy link
Member

No description provided.

@marc-hanheide
Copy link
Member Author

then we need to test parameters and find a stable set

@Jailander
Copy link
Member

We (me and @cdondrup ) just did some testing on this, the base_local_planner was not an improvement, the problem is that it rejected a lot of goals without even trying, and it sometimes quitted the navigation when an obstacle first appeared, even though overall the trajectories were smoother.

Seeing this we decided to try different parameter configurations on the dwa_planner, the first finding was the you can deactivate the dwa approach by setting the use_dwa parameter to false this led to a smother behaviour, but the robot was unable to go across doors anymore, so we decided to play with the parameters a bit and found that setting min_trans_vel: 0.0 made the robot turn on the stop and led to a generally more robust behaviour.

I think this needs further testing, do you think we can get anyone else to verify this. I leave the final parameter configuration for the dwa planner on our tests

DWAPlannerROS: {
  acc_lim_th: 2.0, 
  acc_lim_theta: 3.2,
  acc_lim_x: 1.0,
  acc_lim_y: 0.0,
  acc_limit_trans: 0.1,
  angular_sim_granularity: 0.1,
  forward_point_distance: 0.325,
  goal_distance_bias: 9.0,
  holonomic_robot: false,
  latch_xy_goal_tolerance: true,
  max_rot_vel: 1.0,
  max_scaling_factor: 0.2, 
  max_trans_vel: 0.55,
  max_vel_x: 0.55,
  max_vel_y: 0.0,
  min_rot_vel: 0.2,
  min_trans_vel: 0.0,
  min_vel_x: 0.0,
  min_vel_y: 0.0,
  occdist_scale: 0.01,
  oscillation_reset_angle: 0.2,
  oscillation_reset_dist: 0.05,
  path_distance_bias: 5.0,
  prune_plan: true,
  restore_defaults: false,
  rot_stopped_vel: 0.1,
  scaling_speed: 0.25,
  sim_granularity: 0.025,
  sim_time: 1.7,
  stop_time_buffer: 0.2,
  trans_stopped_vel: 0.0,
  use_dwa: true,
  vth_samples: 20,
  vx_samples: 3,
  vy_samples: 10,
  xy_goal_tolerance: 0.3,
  yaw_goal_tolerance: 0.1
}

@cdondrup
Copy link
Member

cdondrup commented Mar 4, 2015

Just a small addendum, we also set the trans_stopped_vel to 0.0 as a consequence of the above changes. Due to the turning on the spot, it also is able to plan out of corners that it usual gets stuck in.

@Jailander
Copy link
Member

yes true thank you @cdondrup

@marc-hanheide
Copy link
Member Author

Excellent, good job! Many, may thanks.
I think the new parameters should be tried by other sites now. @cburbridge @bfalacerda @nilsbore @hawesie @yianni @lucasb-eyer @ToMadoRe @mzillich you think you want to give this a try and put your observations in here, please? I leave this open until every site has reported their level of happiness and then we shall make the found parameters default in strands_movebase

@nilsbore
Copy link
Member

nilsbore commented Mar 5, 2015

On it! I have similar experiences with the base_local_planner. Didn't explore too much of the parameter space though.

@lucasb-eyer
Copy link
Member

This sounds just right, esp. the *trans*vel part. I'll try to test it soon-ish, though I'm swamped right now.

@cburbridge
Copy link
Member

I have not had a chance to test these parameters yet, but surely we should just have vy_samples: 1 to (presumably) only sample the current y velocity? This might also mask strands-project/strands_morse#96.

@lucasb-eyer
Copy link
Member

ping @vonovak

@bfalacerda
Copy link
Contributor

i got lost here, have these params been merged already?

@nilsbore
Copy link
Member

nilsbore commented Apr 2, 2015

I think they have, and it's working fine here.

@nilsbore
Copy link
Member

nilsbore commented Apr 2, 2015

Or.. Looking at https://github.com/strands-project/strands_movebase/blob/indigo-devel/strands_movebase/strands_movebase_params/dwa_planner_ros.yaml, it doesn't seem like it, in particular I don't see trans_stopped_vel and min_trans_vel.

@bfalacerda
Copy link
Contributor

@Jailander @cdondrup could you make a PR so I can put it in bob more easily?

@Jailander
Copy link
Member

Ok

@bfalacerda
Copy link
Contributor

in the place we have bob nav works well anyway, so we can't really see the benefits of these params. Given https://github.com/strands-project/g4s_deployment/issues/8 , maybe we should at least try them in simulation? Can someone do it? @kunzel ?

@lucasb-eyer
Copy link
Member

In our place they may be extremely beneficial, but I don't have the time to test them until in two and a half weeks, deadlines and meetings in the other project...

@vonovak
Copy link

vonovak commented Jun 17, 2015

The robot does behave better with the *trans*vel = 0

Also: Setting the forward_point_distance parameter to 0 improves how the robot is turning on the spot. Instead of oscillating left and right in some situations, it can make a full ~180 deg. turn. Also, increasing angular_sim_granularity to about 0.4 sometimes made the robot on-the-spot rotations a bit less jerky.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

8 participants