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

gmapping + iRobot Create + Hokuyo laser scanner

asked 2011-03-22 15:02:14 -0500

Pi Robot gravatar image

updated 2014-01-28 17:09:24 -0500

ngrennan gravatar image

Hello ROS fans,

I have a general question about using slam_gmapping with an iRobot Create and a Hokuyo laser scanner (model URG-04LX-UG01). I understand that the odometry on the Create is a little shaky and I can see this by doing an "out and back" test using odometry alone--the Create ends up quite a ways from the starting point. So now I am trying gmapping using the Brown irobot_create_2_1 driver to provide odometry and the laser scanner set to a 240 degree sweep. I can make some fairly good maps of my apartment but I have noticed a phenomenon that I think I sort of understand and was wondering if I can remedy.

Even after a room has been fairly well mapped out, as the Create continues to move about, the points of the laser scan in RViz will often get out of alignment with surrounding map features, like a wall. At that point, the model of the robot in RViz might "teleport" a couple of grid cells in some direction. Then the laser scan points will match up with the map again, and the robot model will make another correction. I'm guessing this represents a kind of battle between what the odometry is telling gmapping versus the laser scan. If so, are there good parameters to set to minimize this?

Below are my various parameter files.

Thanks! patrick


My gmapping node:

  <node name="gmapping" pkg="gmapping" type="slam_gmapping" args="scan:=scan" ou
tput="screen">
    <param name="linearUpdate" value="0.1" />
    <param name="angularUpdate" value="0.05" /> 
    <param name="xmin" value="-20" />   
    <param name="ymin" value="-20" />
    <param name="xmax" value="20" />    
    <param name="ymax" value="20" />
    <param name="maxUrange" value="6" />        
  </node>

base_local_planner_params.yaml:

controller_frequency: 3.0
TrajectoryPlannerROS:
  max_vel_x: 0.2
  min_vel_x: 0.1
  max_rotational_vel: 1.0
  min_in_place_rotational_vel: 0.2
  acc_lim_th: 5.0
  acc_lim_x: 1.0
  acc_lim_y: 1.0
  holonomic_robot: false
  yaw_goal_tolerance: 0.25
  xy_goal_tolerance: 0.2

  goal_distance_bias: 0.8
  path_distance_bias: 0.8
  sim_time: 1.5
  heading_lookahead: 0.325
  oscillation_reset_dist: 0.05

  vx_samples: 10
  vtheta_samples: 40
  dwa: false

costmap_common_params.yaml

obstacle_range: 5.0
raytrace_range: 3.5
robot_radius: 0.17
inflation_radius: 0.65
observation_sources: scan
scan: {sensor_frame: /kinect_depth_frame, data_type: LaserScan, topic: /scan, ma
rking: true, clearing: true}

local_costmap_params.yaml

local_costmap:
   global_frame: /odom
   robot_base_frame: /base_link
   update_frequency: 3.0
   publish_frequency: 0.0
   static_map: false
   rolling_window: true
   width: 4.0
   height: 4.0
   resolution: 0.1
   transform_tolerance: 0.5

global_costmap_params.yaml

global_costmap:
   global_frame: /map
   robot_base_frame: /base_link
   update_frequency: 3.0
   publish_frequency: 0.0
   static_map: true
   transform_tolerance: 0.5
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2011-03-22 19:26:58 -0500

That happens because gmapping has one map for every particle and the best particle's map and pose are shown in rviz. If the best particle changes, so does the estimated robot pose and the map. However, the robot pose is updated much more frequently, so you often see the pose estimate of the new best particle, while still looking at the old best map estimate. Looking at gmapping's code it seems a new map is published everytime updateMap() is called. This in turn is called every map_update_interval (which is a gmapping rosparam) seconds. So lowering this should lower the amount of time you see pose and map out of sync. OTOH, this increases computational load and updates the map more often, which can have an impact on overall mapping performance (speed and quality wise). One (pretty invasive) idea would be to optionally let gmapping publish a new map message as soon as the best particle changes.

edit flag offensive delete link more

Comments

Thanks Stephan!
Pi Robot gravatar image Pi Robot  ( 2011-03-23 01:37:44 -0500 )edit

Question Tools

Stats

Asked: 2011-03-22 15:02:14 -0500

Seen: 1,873 times

Last updated: Mar 22 '11