Gmapping the same area creating inaccurate duplication
I'm attempting to map a city simulation using my robot model which is equipped with a laser. I am aware gmapping is used for indoors mapping but I'm attempting to use it on this project.
The laser is positioned low enough on the robot so that its beam is relected off the kerbs of the simulated streets, as shown below:
My problem is 2-fold.
The first problem is as I teleoperate the robot, the map being generated has repeating V-shaped gaps in it. In order to deal with these gaps, I decided to map each street atleast twice but that led to my second problem.
When I bring the robot back onto a previously mapped road, to fix the gaps, the mapping is misaligned from the previous pass.
Both issues shown below :
The section of the screenshot highlighted in red is supposed to be a single street.
I have tried running this multiple times and teleoped the robot as slowly as possible but each time the mapping eventually goes wrong.
Can anyone help me understand what I'm doing wrong and how I might fix these issues ?
*UPDATE : *
Odometry :
The image below shows my robot in rotation on the spot . . . kind of. I had suspected it's rotation was not quite what I expected and enabling the odometry view confirmed it. It drives around a virtual box - I'm not sure yet if this is an error.
Distance and cycle of the scan :
The following is my gazebo plugin code and the urdf for the laser. I know the maximum range is 10 but I'm not sure what the cycle is, probably <samples>720</samples>:
<xacro:macro name="laser_front">
<gazebo reference="hokuyo_link_front">
<sensor type="ray" name="head_hokuyo_sensor_front">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>20</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.5</min_angle>
<max_angle>1.5</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>10.0</max>
<resolution>0.05</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/scan</topicName>
<frameName>hokuyo_link_front</frameName>
</plugin>
</sensor>
</gazebo>
<link name="hokuyo_link_front">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://rrbot_description/meshes/hokuyo.dae"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="laser_joint_front" type="fixed">
<origin xyz="0.53 0 -0.25" rpy="0 0.0 0"/>
<parent link="chasis"/>
<child link="hokuyo_link_front"/>
</joint>
</xacro:macro>
Parameters of gmapping :
Only one parameter setting and that's just to change the base_frame, as shown below ...