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

Revision history [back]

click to hide/show revision 1
initial version

A couple of things:

1) I tried to run in simulation with similar parameters, I'll post them at the bottom of this post, and things worked for me.

2) Its not clear from the video you posted whether or not the local costmap's obstacles are being updated properly. This tutorial shows how to display navigation-relevant information in rviz. Specifically, I'd really like to know whether move_base/local_costmap/obstacles shows anything.

Here are the params I used in stage:

costmap_common_params.yaml

#Set the tolerance we're willing to have for tf transforms
transform_tolerance: 0.3

#Obstacle marking parameters
obstacle_range: 2.5
max_obstacle_height: 2.0
raytrace_range: 3.0

#The footprint of the robot and associated padding
footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.46, 0.0], [0.325, -0.325]]
footprint_padding: 0.01

#Cost function parameters
inflation_radius: 0.55
cost_scaling_factor: 10.0

#The cost at which a cell is considered an obstacle when a map is read from the map_server
lethal_cost_threshold: 100

local_costmap_params.yaml

local_costmap:
  #Set the global and robot frames for the costmap
  global_frame: map
  robot_base_frame: base_link

  #Set the update and publish frequency of the costmap
  update_frequency: 5.0
  publish_frequency: 2.0

  static_map: true
  rolling_window: false

global_costmap_params.yaml

global_costmap:
  #Set the global and robot frames for the costmap
  global_frame: /map
  robot_base_frame: base_link

  #Set the update and publish frequency of the costmap
  update_frequency: 5.0
  publish_frequency: 0.0

  #We'll use a map served by the map_server to initialize this costmap
  static_map: true
  rolling_window: false

base_local_planner_params.yaml

TrajectoryPlannerROS:
  #Set the acceleration limits of the robot
  acc_lim_th: 4.0
  acc_lim_x: 3.7
  acc_lim_y: 3.5

  #Set the velocity limits of the robot
  max_vel_x: 0.2
  min_vel_x: 0.05
  max_rotational_vel: 0.3
  min_in_place_rotational_vel: 0.05

  #The velocity the robot will command when trying to escape from a stuck situation
  escape_vel: -0.1

  #For this example, we'll use a holonomic robot
  holonomic_robot: true

  #Since we're using a holonomic robot, we'll set the set of y velocities it will sample
  y_vels: [-0.3, -0.1, 0.1, 0.3]

  #Set the tolerance on achieving a goal
  xy_goal_tolerance: 0.1
  yaw_goal_tolerance: 0.05

  #We'll configure how long and with what granularity we'll forward simulate trajectories
  sim_time: 1.7
  sim_granularity: 0.025
  vx_samples: 3
  vtheta_samples: 20

  #Parameters for scoring trajectories
  goal_distance_bias: 0.8
  path_distance_bias: 0.6
  occdist_scale: 0.01
  heading_lookahead: 0.325

  #We'll use the Dynamic Window Approach to control instead of Trajectory Rollout for this example
  dwa: true

  #How far the robot must travel before oscillation flags are reset
  oscillation_reset_dist: 0.05

  #Eat up the plan as the robot moves along it
  prune_plan: true

Hope this helps.