Hi Mike,

I'm also working on driving a wheelchair with the nav stack (or at least, a robot built on top of a powerwheelchair base), so we probably have had similar experiences. See replies inline.

On Thu, Nov 18, 2010 at 5:15 PM, Michael Sands <m.sands.vader@gmail.com> wrote:
All,

I'm working on driving a wheelchair with the navigation stack. When using the base local planner I've noticed that the path between two waypoints is not straight even if there are no obstacles between them.

Is this the path output by the global planner (NavFn) or what base_local_planner ends up telling the base to do while following a straight line path? If you can put together a simulation of the entire nav_stack and environment in Stage, it may help us to find a good set of parameters or fix any bugs you have uncovered.
 
Also, the robot oscillates around the path, even with the path_distance_bias set very high and doesn't settle and follow the path. We are not moving very quickly and I figure I must be doing something wrong. Anyone have any ideas?

So, whenever I've played with the bias terms on the base_local_planner, I've always seen an interdependence between the path_distance_bias and goal_distance_bias terms in order to get the behavior I wanted. There are two extremes: 
  • path_distance_bias >>> goal_distance_bias makes for a robot that basically sits on the path and never wants to leave it - easiest way to not leave the path is to basically do nothing or just rotate in place.
  • goal_distance_bias >>> path_distance_bias makes for a robot that heads directly toward the goal, more or less ignoring the planned path
In my experience, path_distance_bias = 5 and goal_distance_bias = 0.1 is squarely in the first case, so I'm not really surprised by the oscillation you are seeing around the path with little to no movement towards the goal. Try increasing your goal_distance_bias and see if that helps.

Looking at my config files, looks like we've been running with the following bias terms:
path_distance_bias: 5.0
goal_distance_bias: 0.8
occdist_scale: 0.05
 
These were setup to try to get the base to precisely follow a path through a narrow doorway and it got partially through most of the time. They are also currently being used for a robotic tour guide under development (again on a wheelchair base) and we've had pretty good results.

Hope that helps.

- Eric


I'm using C-turtle

base_local_planner_parameters.yaml:
TrajectoryPlannerROS:
  max_vel_x: 0.45
  min_vel_x: 0.2
  max_rotational_vel: 0.6
  min_in_place_rotational_vel: 0.1
  backup_vel: -0.4

  acc_lim_th: 0.5
  acc_lim_x: 0.3
  acc_lim_y: 2.5

  holonomic_robot: false

  yaw_goal_tolerance: 7.0
  xy_goal_tolerance: 0.8
  path_distance_bias: 5.0
  goal_distance_bias: 0.1
  heading_lookahead: 1.0
  heading_scoring: false
  dwa: false
  oscillation_reset_dist: 0.05

  sim_time: 3.0
  vx_samples: 3
  vtheta_samples: 40

Thanks for your help,

Mike Sands

_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users