Diff Drive Plugin Drift Problem
I am facing issue using the gazebo differential drive controller. The robot moves however it doesn't exactly move in a straight line when I issue /cmd_vel x="0.05". The robot will start to drift gradually. Appreciate any help thanks. I have tried increasing the mass and also ensuring the inertia is not tilted. Also, when I check the /joint_states topic each of the wheel joint has slightly different position.
<?xml version="1.0" ?>
<robot name="alphabot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find alphabot_description)/urdf/materials.xacro" />
<xacro:include filename="$(find alphabot_description)/urdf/alphabot.trans" />
<xacro:include filename="$(find alphabot_description)/urdf/alphabot.gazebo" />
<link name="base_link">
<inertial>
<origin xyz="3.9964129120210354e-17 -1.949783532853795e-05 0.014547668321607015" rpy="0 0 0"/>
<mass value="0.2"/>
<inertia ixx="0.000125" iyy="0.000266" izz="0.000389" ixy="-0.0" iyz="-0.0" ixz="0.0"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://alphabot_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://alphabot_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="spacer_1_1">
<inertial>
<origin xyz="-8.554354349876725e-08 -2.7824964554667986e-15 0.020056162439080906" rpy="0 0 0"/>
<mass value="0.05"/>
<inertia ixx="1e-06" iyy="1e-06" izz="0.0" ixy="-0.0" iyz="0.0" ixz="-0.0"/>
</inertial>
<visual>
<origin xyz="-0.028948 -0.04191 -0.017048" rpy="0 0 0"/>
<geometry>
<mesh filename="package://alphabot_description/meshes/spacer_1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="gold"/>
</visual>
<collision>
<origin xyz="-0.028948 -0.04191 -0.017048" rpy="0 0 0"/>
<geometry>
<mesh filename="package://alphabot_description/meshes/spacer_1_1.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="spacer_1_2">
<inertial>
<origin xyz="-8.554354354040061e-08 -2.7755575615628914e-15 0.020056162439080906" rpy="0 0 0"/>
<mass value="0.05"/>
<inertia ixx="1e-06" iyy="1e-06" izz="0.0" ixy="-0.0" iyz="0.0" ixz="-0.0"/>
</inertial>
<visual>
<origin xyz="-0.028948 0.04191 -0.017048" rpy="0 0 0"/>
<geometry>
<mesh filename="package://alphabot_description/meshes/spacer_1_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="gold"/>
</visual>
<collision>
<origin xyz="-0.028948 0.04191 -0.017048" rpy="0 0 0"/>
<geometry>
<mesh filename="package://alphabot_description/meshes/spacer_1_2.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="spacer_1_3">
<inertial>
<origin xyz="8.554362094723156e-08 -2.7824964554667986e-15 0.02005616243908087" rpy="0 0 0"/>
<mass value="0.05"/>
<inertia ixx="1e-06" iyy="1e-06" izz="0.0" ixy="-0.0" iyz="0.0" ixz="-0.0"/>
</inertial>
<visual>
<origin xyz="0.028948 0.04191 -0.017048" rpy="0 0 0"/>
<geometry>
<mesh filename="package://alphabot_description/meshes/spacer_1_3.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="gold"/>
</visual>
<collision>
<origin xyz="0.028948 0.04191 -0.017048" rpy="0 0 0"/>
<geometry>
<mesh filename="package ...