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

yaw_goal_tolerance not working? [closed]

asked 2012-11-07 09:11:56 -0600

I know that this question is common but I think that I've looked "all over" for an answer that works so if you have a minute would you mind checking out these config files for the nav stack? Everything seems to be working just great except for the goal achievement. I'm going to say that it gets to the (x,y) component fine but then it rotates back and forth. Ready... Set... Check my yaw_goal_tolerance :-) Just kidding, is it possible that the rotation actions being provided by the local planner are too coarse?

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: 10.0
  height: 10.0
  origin_x: 0.0
  origin_y: 0.0
  resolution: 0.05

global_costmap:
  global_frame: /map
  robot_base_frame: /base_link
  update_frequency: 2.0
  publish_frequency: 10.0
  static_map: false
  rolling_window: true

obstacle_range: 2.5
raytrace_range: 3.0
inflation_radius: 0.5


#---standard pioneer footprint---

#---(in meters)---
footprint: [ [0.254, -0.0508], [0.1778, -0.0508], [0.1778, -0.1778], [-0.32, -0.1778], [-0.32, 0], [-0.32, 0.1778], [0.1778, 0.1778], [0.1778, 0.0508], [0.254, 0.0508] ]

transform_tolerance: 0.5
map_type: costmap

observation_sources: scan

scan: {
      sensor_frame: base_laser, 
      data_type: LaserScan, 
      topic: scan, 
      marking: true, 
      clearing: true, 
      expected_update_rate: 0.5
      } 

# Robot Configuration Parameters
acc_lim_x: 2.5
acc_lim_y: 2.5
acc_lim_th: 3.2
max_vel_x: 0.5
min_vel_x: 0.1
max_rotational_vel: 1.75
min_in_place_rotational_vel: 0.4
escape_vel: -0.1
holonomic_robot: false

# Goal Tolerance Parameters
xy_goal_tolerance: 0.5
yaw_goal_tolerance: 0.1

# Forward Simulation Parameters
sim_time: 1.7
sim_granularity: 0.025
vx_samples: 3
vtheta_samples: 20

# Trajectory Scoring Parameters
goal_distance_bias: 0.8
path_distance_bias: 0.6
occdist_scale: 0.01
heading_lookahead: 0.325
dwa: true

# Oscillation Prevention Parameters
oscillation_reset_dist: 0.05

If these settings look rather familiar it's because they're just about copied from the erratic navigation stack. And for completeness I've up'ed the xy_goal_tolerance to 0.5 and the yaw_goal_tolerance to 3.0 without having any improvement.

I saw that someone had an issue where they created a discrepancy between the resolutions of the map and costmaps?

So with that being said here are the parameters I'm feeding to gmapping:

<param name="sigma" value="0.05"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.05"/>
<param name="astep" value="0.05"/>
<param name="iterations" value="5"/>
<param name="lsigma" value="0.075"/>
<param name="ogain" value="3.0"/>
<param name="lskip" value="0"/>
<param name="srr" value="0.01"/>
<param name="srt" value="0.02"/>
<param name="str" value="0.01"/>
<param name="stt" value="0.02"/>
<param name="linearUpdate" value="0.5"/>
<param name="angularUpdate" value="0.436"/>
<param name="temporalUpdate" value="-1.0"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="80"/>
<param name="xmin" value="-10.0" />
<param name="ymin" value="-10.0" />
<param name="xmax" value="10.0" />
<param name="ymax" value="10.0" />
<param name="delta" value="0.025"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01 ...
(more)
edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by skiesel
close date 2013-10-11 04:39:16

Comments

weiin gravatar image weiin  ( 2012-11-07 14:17:29 -0600 )edit

I had tried looking through it. But I wanted to make sure that I had tried everything. As far as I can tell I've played all the parameters in the known universe. I eventually thought that maybe my max/min acc and vel were off because it looked like the planner was "overshooting". Still didn't fixit

skiesel gravatar image skiesel  ( 2012-11-13 02:30:17 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2012-11-13 03:56:59 -0600

It looks like the issue was a namespacing problem. The TrajectoryPlannerROS was not receiving the correct parameters. The parameters were being loaded to /move_base but not /move_base/TrajectoryPlannerROS.

The solutions that I found were to either add "TrajectorPlannerROS:" to the top of the yaml file containing the parameters for the planner (in my case base_local_planner_params.yaml), just make sure that any parameters in the file have two spaces in front of them or you'll end up with a mysterious error when you try to launch.

TrajectoryPlannerROS:
  holonomic_robot: false

Notice the two spaces in front of the parameter.

The second solution is to namespace the file when you load it, which allows you to reuse the file in multiple namespaces for common parameters. Inside of the launch file, inside of the move_base node:

<rosparam file="base_local_planner_params.yaml" command="load" ns="TrajectoryPlannerROS"/>
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2012-11-07 09:11:56 -0600

Seen: 1,176 times

Last updated: Nov 13 '12