Choosing the right coefficients for Gazebo simulation
Hello, I am trying to create an URDF and simulate it in Gazebo for a 4WD Skid steering robot. The chasis is actually a box with the following properties:
and wheels:
I have created the URDF and a differential drive plugin for gazebo to simulate the model but I have no idea how to choose appropriate values for torque, mu1, mu2, kp, kd and inertia matrix. The values that I am currently using are taken/combined from the erratic/guardian/turtlebot stacks.
By publishing the odometry (calculated in the plugin) and comparing the robot's position in Gazebo and RViz I can see that the model slips a lot while performing turns.
Relevant files: myrobot.urdf.xacro myrobot_constants.xacro myrobot_wheel.xacro myrobot_materials.xacro
Any help is appreciated.
Thanks in advance.
Update:
Here is the output from Solidworks for the chassis:
Output coordinate System: -- default --
Mass = 489.90 grams
Volume = 181445.50 cubic millimeters
Surface area = 189380.73 millimeters^2
Center of mass: ( millimeters )
X = 41.53
Y = 93.76
Z = 131.23
Principal axes of inertia and principal moments of inertia: ( grams *
square millimeters )
Taken at the center of mass.
Ix = (0.00, 0.01, 1.00) Px = 4157521.05
Iy = (1.00, 0.00, 0.00) Py = 5704820.80
Iz = (0.00, 1.00, -0.01) Pz = 9356042.65
Moments of inertia: ( grams * square millimeters )
Taken at the center of mass and aligned with the output coordinate system.
Lxx = 5704820.80 Lxy = 0.00 Lxz = -0.00
Lyx = 0.00 Lyy = 9355391.53 Lyz = 58176.21
Lzx = -0.00 Lzy = 58176.21 Lzz = 4158172.18
Moments of inertia: ( grams * square millimeters )
Taken at the output coordinate system.
Ixx = 18448329.91 Ixy = 1907623.47 Ixz = 2669963.78
Iyx = 1907623.47 Iyy = 18637105.26 Iyz = 6086030.51
Izx = 2669963.78 Izy = 6086030.51 Izz = 9309884.18
And here is how I've put it in URDF:
<link name="base_link">
<inertial>
<mass value="${chassis_mass}" />
<origin xyz="0.04153 0.09376 0.13123" />
<inertia ixx="0.00415752105" ixy="0.0" ixz="0.0"
iyy="0.0057048208" iyz="0.0"
izz="0.00935604265" />
</inertial>
Is this correct? I guess this is only correct if my model has the coordinate system aligned with the representation from Gazebo, right?
the update URDF block for base_link ineria looks right. Yes, assuming the coordinate system from your SWX export aligns with the coordinate of the URDF Link. Can you update the inertia blocks of the attached xacro files? Can you also post an approximation of slippage in your simulation? Thanks.