[ros-users] TrajectoryPlannerROS does not take parameter

Christian Verbeek verbeek at servicerobotics.eu
Tue Jun 15 07:35:52 UTC 2010


Dear Eitan,

The most critical configuration is base_local_planner_params. I am
playing around with this for three days now and I am not able to find a
satisfactory setting. My robot is quite big (radius 0.46m) and  our
office space is narrow. Depending on its starting position the planner
makes a good job once and during the next run it fails to find a path. I
also saw the robot driving the whole path backwards! I mean, this should
never happen.

I got the navigation stack running with our smaller robot "Robotino".
This one has only 0.16m radius and is holonomic so it has much more
space to move in our office. The big platform discussed here is really a
challenge. You can see a video of the big platform moving in our office
at http://www.servicerobotics.eu/index.php?id=25&L=0

Here are the navigation stack config files.

**********move_base.launch******************
<launch>
  <!--- Run mapserver -->
  <include file="$(find f5_navigation)/map_server.launch" />
 
  <!--- Run AMCL -->
  <include file="$(find amcl)/examples/amcl_diff.launch" />

  <node pkg="move_base" type="move_base" respawn="false"
name="move_base" output="screen">
    <rosparam file="$(find
f5_navigation)/config/costmap_common_params.yaml" command="load"
ns="global_costmap" />
    <rosparam file="$(find
f5_navigation)/config/costmap_common_params.yaml" command="load"
ns="local_costmap" />
    <rosparam file="$(find
f5_navigation)/config/local_costmap_params.yaml" command="load" />
    <rosparam file="$(find
f5_navigation)/config/global_costmap_params.yaml" command="load" />
    <rosparam file="$(find
f5_navigation)/config/base_local_planner_params.yaml" command="load" />
  </node>
</launch>
**********move_base.launch******************

**********costmap_common_params.yaml*******
obstacle_range: 2.5
raytrace_range: 3.0
#width=0,75
#length=0.8 + 0.08 laser rangefinder
#footprint: [[-0.4, 0.375], [-0.4, -0.375], [0.48, -0.375], [0.48, 0.375]]
robot_radius: 0.46
inflation_radius: 0.5

observation_sources: laser_scan_sensor

laser_scan_sensor: {sensor_frame: laser_link, data_type: LaserScan,
topic: scan, marking: true, clearing: true}
**********costmap_common_params.yaml*******

**********local_costmap_params.yaml**********
local_costmap: {
  global_frame: odom,
  robot_base_frame: base_link,
  update_frequency: 5.0,
  publish_frequency: 2.0,
  static_map: false,
  rolling_window: true,
  width: 3.0,
  height: 3.0,
  resolution: 0.05 }
**********local_costmap_params.yaml**********

**********global_costmap_params.yaml**********
global_costmap: {
  global_frame: /map,
  robot_base_frame: base_link,
  update_frequency: 5.0,
  static_map: true }
**********global_costmap_params.yaml**********

**********base_local_planner_params.yaml**********
TrajectoryPlannerROS:
  max_vel_x: 0.2
  min_vel_x: 0.05
  max_rotational_vel: 0.4
  min_in_place_rotational_vel: 0.15

  acc_lim_th: 1.0
  acc_lim_x: 0.1
  acc_lim_y: 0.1

  #2.8grad Genauigkeit
  yaw_goal_tolerance: 0.05
  xy_goal_tolerance: 0.2

  sim_time: 2.0
  sim_granularity: 0.01
  vx_samples: 50
  vtheta_samples: 50
  controller_frequency: 20.0
 
  #path_distance_bias: 1.5
  #goal_distance_bias: 0.8
  #heading_lookahead: 0.5
  #heading_scoring: true
  #heading_scoring_timestep: 1.2

  occdist_scale: 0.01
  #dwa: false
 
  #oscillation_reset_dist: 0.02
 
  holonomic_robot: false
**********base_local_planner_params.yaml**********

-- 
___________________________________________
REC GmbH
Dr. Christian Verbeek
Robert-Koch-Str. 2, 82152 Planegg

Tel:    +49 89 85689672
Fax:    +49 89 85902327
Mobile: +49 160 7056589
e-mail: verbeek at servicerobotics.eu

Geschäftsführer: Dr. Christian Verbeek
Registergericht: AG München (HRB 154463)
____________________________________________ 





More information about the ros-users mailing list