Robot simulation wheels spinning on the spot malfunction
My URDF is loading in Gazebo and I issue a twist command to move the robot along the x-axis.
The problem is the wheels malfunction by spinning instead of rotating and moving the robot as shown in the image below:
I would appreciate some help with this.
My urdf code is below:
<?xml version="1.0"?>
<robot name="mybot">
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<legacyMode>false</legacyMode>
<alwaysOn>true</alwaysOn>
<publishWheelTF>true</publishWheelTF>
<publishTf>1</publishTf>
<publishWheelJointState>true</publishWheelJointState>
<updateRate>100.0</updateRate>
<leftJoint>left_wheel_joint</leftJoint>
<rightJoint>right_wheel_joint</rightJoint>
<wheelSeparation>1.1</wheelSeparation>
<wheelDiameter>0.52</wheelDiameter>
<wheelAcceleration>1.0</wheelAcceleration>
<torque>20</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<robotBaseFrame>base_link</robotBaseFrame>
</plugin>
</gazebo>
<material name="blue">
<color rgba="0 0 0.8 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.015" radius="0.2"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<geometry>
<cylinder length="0.015" radius="0.2"/>
</geometry>
<material name="white"/>
</collision>
<inertial>
<origin xyz="0 0 1" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<link name="upper_level">
<visual>
<geometry>
<cylinder length="0.015" radius="0.2"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<geometry>
<cylinder length="0.015" radius="0.2"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 1" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<joint name='upper_level_joint' type='fixed'>
<parent link='base_link'/>
<child link='upper_level'/>
<origin rpy='0 0 0' xyz='0 0 0.05'/>
</joint>
<link name='seperator_1'>
<visual>
<origin rpy='0 0 0' xyz='-0.120 0.085 -0.02'/>
<material name='white'/>
<geometry>
<cylinder length='0.07' radius='0.003'/>
</geometry>
</visual>
<collision>
<material name='white'/>
<geometry>
<cylinder length='0.07' radius='0.003'/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 1" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<joint name='upper_level_sperator_1_joint' type='fixed'>
<parent link='upper_level'/>
<child link='seperator_1'/>
<origin xyz='0 0 0'/>
</joint>
<link name='seperator_2'>
<visual>
<origin rpy='0 0 0' xyz='-0.120 -0.085 -0.02'/>
<material name='white'/>
<geometry>
<cylinder length='0.07' radius='0.003'/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder length='0.07' radius='0.003'/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 1" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<joint name='upper_level_sperator_2_joint' type='fixed'>
<parent link='upper_level'/>
<child link='seperator_2'/>
<origin xyz='0 0 0'/>
</joint>
<link name='seperator_3'>
<visual>
<origin ...