gmapping + iRobot Create + Hokuyo laser scanner
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