Hello,
I’m experiencing issues with joint velocity oscillations in Gazebo while simulating a robot using ROS 2 and ros2_control
. I’ve configured a tricycle drive robot with the following components:
- Base Link: A large base with a mass of
60 kg
(scaled down from the real robot’s mass of2500 kg
) and a center of mass offset. - Steering Link: A link for front-wheel steering, connected via a continuous joint.
- Traction Wheel: A drive wheel with a mass of
15 kg
. - Rear Wheels: Two supporting rear wheels with a mass of
2 kg
each.
The problem is that the reported wheel velocities (via /joint_states
) oscillate significantly.
: Increasing solver iterations (iters=400
) noticeably improved the behavior but didn’t fully resolve the velocity oscillations.
I scaled down the mass and inertia of every part of the robot (from a real-world mass of 2500 kg
to a simulated mass of ~60 kg
for the base link).
Played with friction coefficients (mu1
, mu2
) and damping (kp
, kd
) across all wheels.
I’m using gazebo version 11 on ros2 humble
gazebo>
$(find robot_description)/config/my_robot_controllers.yaml
<ros2_control name=“GazeboSystem” type=“system”>
gazebo_ros2_control/GazeboSystem
<command_interface name=“position” />
<state_interface name=“position” />
<state_interface name=“velocity” />
<state_interface name=“effort”/>
</joint>
<joint name="traction_joint">
<command_interface name="velocity" />
<state_interface name="position" />
<state_interface name="velocity" />
<state_interface name="effort"/>
</joint>
<link name="base_footprint"/>
<joint name="base_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin xyz="0.0 0.0 0.04" rpy="0 0 0"/>
</joint>
<link name="base_link">
<inertial><!-- The mass and inertia are divided by 60, the Gazebo engine (ODE) seem to have trouble with large mass-->
<origin xyz="1.131 0.0 0.89" rpy="0 0 0" />
<mass value="60" />
<inertia ixx="43.17" ixy="-0.11" ixz="-5.81"
iyy="48.53" iyz="0.09" izz="18.5" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="file://$(find robot_description)/meshes/base_link.stl" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="file://$(find robot_description)/meshes/base_link.stl" />
</geometry>
</collision>
</link>
<gazebo reference="base_link">
<material>Gazebo/Gray</material>
</gazebo>
<link name="traction_wheel_link">
<visual>
<geometry>
<cylinder length="0.08" radius="0.155" />
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="15" />
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1" />
</inertial>
<collision >
<geometry>
<cylinder length="0.08" radius="0.155" />
</geometry>
</collision>
</link>
<joint name="traction_joint" type="continuous">
<parent link="${parent}" />
<child link="traction_wheel_link" />
<origin xyz="0 0 0.0" rpy="-1.57 0 0" />
<axis xyz="0 0 1" />
<dynamics damping="0.5" friction="0.7" />
</joint>
<gazebo reference="traction_wheel_link">
<material>Gazebo/Black</material>
<mu1>0.7</mu1>
<mu2>0.7</mu2>
</gazebo>
<!-- <link name="${prefix}_wheel_link">
<inertial>
<origin xyz="-1.94289029309402E-16 -0.0571500000000001 0" rpy="0 0 0" />
<mass value="1.47749436881024" />
<inertia ixx="0.00226827782805257" ixy="-3.16660954114216E-18" ixz="0"
iyy="0.00136627908669598" iyz="-4.10206903007842E-35" izz="0.00226827782805257" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="$(find robot_description)/meshes/small_wheel_link.STL" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="$(find robot_description)/meshes/small_wheel_link.STL" />
</geometry>
</collision>
</link>
<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="${x} ${y} ${z}" rpy="0 0 0" />
<parent link="${parent}" />
<child link="${prefix}_wheel_link" />
<axis xyz="0 -1 0" />
<dynamics damping="0.1" friction="0.1" />
</joint>
<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/Black</material>
</gazebo> -->
<!-- right wheel Link -->
<link name="${prefix}_wheel_link">
<collision>
<geometry>
<cylinder length="0.08" radius="0.06" />
</geometry>
</collision>
<visual>
<geometry>
<cylinder length="0.08" radius="0.06" />
</geometry>
<material name="Black" />
</visual>
<inertial>
<mass value="2" />
<inertia ixx="0.145833" ixy="0.0" ixz="0.0" iyy="0.145833" iyz="0.0" izz="0.125" />
</inertial>
</link>
<!-- right wheel joint -->
<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="${x} ${y} ${z}" rpy="-1.57 0 0" />
<parent link="${parent}" />
<child link="${prefix}_wheel_link" />
<axis xyz="0 0 1" />
<dynamics damping="0.0" friction="0.2" />
</joint>
<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/Black</material>
<mu1>0.7</mu1>
<mu2>0.7</mu2>
</gazebo>
<link name="steering_link">
<visual>
<geometry>
<box size="0.01 0.01 0.01" />
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.5" />
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
</link>
<joint name="steering_joint" type="continuous">
<origin xyz="1.75 0 0.115" rpy="0 0 0" />
<parent link="${parent}" />
<child link="steering_link" />
<axis xyz="0 0 1" />
<dynamics damping="0.5" friction="0.5" />
</joint>
<gazebo reference="steering_link">
<material>Gazebo/Red</material>
</gazebo>