Closed goekce closed 3 years ago
Hi @goekce Looks like the inertial values need to be revised. I'll update these values soon. Thanks for reporting the issue!
I recently noticed that the robot flies if I place TB3 Waffle Pi on the empty world in Gazebo. I noticed that the default parameters for the ode solver do not suffice to appropriately simulate TB3 physics. I have to change ode solver iters
parameter to 150 to avoid flying as Robotis does in its worlds, e.g.,:
Here is a minimal world with minimal parameters:
<?xml version='1.0' ?>
<sdf version='1.7'>
<world name="world">
<physics type="ode">
<ode>
<solver>
<iters>150</iters>
</solver>
</ode>
</physics>
<include><name>sun</name><uri>model://sun</uri></include>
<include><name>ground</name><uri>model://ground_plane</uri></include>
<include><name>tb3</name><uri>model://turtlebot3_waffle_pi</uri><pose>0.5 0.5 0 0 0 1.5707963267948966</pose></include>
</world>
</sdf>
If you remove iters
(then it is set to 50) then the robot flies. Maybe SDFormat default parameters were changed recently. I use Gazebo 11.4.
Hi,
The iters
tag governs the simulation frequency and higher value uses more resource to create more accurate simulation result.
The drifting is actually caused by incorrect inertia value of left and right wheels, and they can be fixed by modifying /turtlebot3_simulations/turtlebot3_gazebo/models/turtlebot3_waffle_pi/model.sdf
file as below.
In line 168, where wheel_left_link
is defined,
<link name="wheel_left_link">
<inertial>
<pose>0.0 0.144 0.023 -1.57 0 0</pose>
<inertia>
<ixx>1.8158194e-03</ixx>
<ixy>-9.3392e-12</ixy>
<ixz>1.04909e-11</ixz>
<iyy>3.2922126e-03</iyy>
<iyz>5.75694e-11</iyz>
<izz>1.8158194e-03</izz>
</inertia>
<mass>2.8498940e-02</mass>
</inertial>
In line 226, where wheel_right_link
is defined,
<link name="wheel_right_link">
<inertial>
<pose>0.0 -0.144 0.023 -1.57 0 0</pose>
<inertia>
<ixx>1.8158194e-03</ixx>
<ixy>-9.3392e-12</ixy>
<ixz>1.04909e-11</ixz>
<iyy>3.2922126e-03</iyy>
<iyz>5.75694e-11</iyz>
<izz>1.8158194e-03</izz>
</inertia>
<mass>2.8498940e-02</mass>
</inertial>
How did you calculate these values Will?
I'll leave the issue here until it is fixed in the codebase.
:heart_decoration: for the quick fix! After applying it the TB3 still drifts on my system. Can you please check again?
@goekce
The inertial value is calculated by the CAD tool based on the 3D modeling file.
I ran a quick test on Gazebo after modifying these values, and the issue was resolved, but I'll check again.
This fix will be updated on foxy-devel
branch and released in this week.
Thanks!
I installed the foxy-devel
branches of turtlebot3
and turtlebot3_simulations
branches from scratch, and now the drifting is gone :partying_face: Somehow it was not enough to only patch the TB3 Waffle Pi model.
I also do not need <iters>150</iters>
anymore. The default setting of sdformat (50) seems to be sufficient. The flying robot was probably also caused by the wrong inertia setting.
@goekce The inertial value is calculated by the CAD tool based on the 3D modeling file. I ran a quick test on Gazebo after modifying these values, and the issue was resolved, but I'll check again. This fix will be updated on
foxy-devel
branch and released in this week. Thanks!
What CAD tool did you use? Did it allow you to set a mass or did it give it to you based on a density of 1? @ROBOTIS-Will
Using ROS2 foxy and
turtlebot_simulations
v. 2.2.2.I start the simulation without any controlling node:
Robot slowly drifts as follows. The sudden movement at the beginning is due to simulation restart:
I would expect that the robot would stop when the motors are not driven. I also tried to stop the robot using
teleop_keyboard
after which the robot still drifts.I tinkered around with wheel friction parameters which did not help, e.g., here:
https://github.com/ROBOTIS-GIT/turtlebot3_simulations/blob/7603541b97ee824ca41e45c8d2a026eaa36b17e7/turtlebot3_gazebo/models/turtlebot3_waffle_pi/model.sdf#L186-L220
Can someone help me with this?