fetch_gazebo
fetch_gazebo copied to clipboard
[BUG] Terrible control on freight robot without casters
Describe the bug
I've been struggling with commanding the freight robot in gazebo. I had noticed that the full fetch
robot worked fine, so I started looking into the differences between them until I could determine the issue.
As it turns out, the freight
robot just needed some casters to be controlled reasonably.
To Reproduce
To reproduce the error, build fetch_gazebo
on branch gazebo11
for ROS Noetic on Ubuntu 20.04.
- On one terminal, launch the simulation:
roslaunch fetch_gazebo playground.launch robot:=freight
- On a second terminal, launch teleop:
rosrun teleop_twist_keyboard teleop_twist_keyboard.py
Request the robot to move forward by pressing i
on the keyboard.
Expected behavior The robot should go forward.
Screenshots
Robot without casters (it doesn't even move forward, it ends up curving over time and has lots of jitter):
Robot with casters (similar to the navigation of the full robot):
catkin workspace (please complete the following information):
- fetch_gazebo version: gazebo11
- Ubuntu version: 20.04
- ROS version: Noetic
Solution
Add the following to freight.gazebo.xacro
:
<xacro:macro name="caster" params="prefix joint_x joint_y">
<link name="${prefix}_caster_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0601"/> <!-- 0.06033 -->
</geometry>
<material name="">
<color rgba="0.086 0.506 0.767 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0601"/>
</geometry>
</collision>
<inertial>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.01"/>
</inertial>
</link>
<gazebo reference="${prefix}_caster_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<kp>100000000</kp>
<kd>10.0</kd>
<maxVel>10</maxVel>
<minDepth>0.001</minDepth>
</gazebo>
<joint name="${prefix}_caster_joint" type="fixed">
<parent link="base_link"/>
<child link="${prefix}_caster_link"/>
<origin rpy="0 0 0" xyz="${joint_x} ${joint_y} 0.055325"/>
<axis xyz="0 1 0"/>
</joint>
</xacro:macro>
<xacro:caster prefix="fl" joint_x="0.15" joint_y="0.12"/>
<xacro:caster prefix="fr" joint_x="0.15" joint_y="-0.12"/>
<xacro:caster prefix="br" joint_x="-0.2" joint_y="0.12"/>
<xacro:caster prefix="bl" joint_x="-0.2" joint_y="-0.12"/>