Skip to content

Commit

Permalink
Inertia fix
Browse files Browse the repository at this point in the history
  • Loading branch information
luis-camero committed Oct 16, 2023
1 parent 7a5cf6d commit ef3f9c6
Showing 1 changed file with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,9 @@
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
<mass value="${wheel_mass}"/>
<inertia
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
ixx="${wheel_mass / 12.0 * (3*wheel_radius*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
iyy="${wheel_mass / 12.0 * (3*wheel_radius*wheel_radius + wheel_len*wheel_len)}" iyz="0.0"
izz="${wheel_mass / 2.0 * wheel_radius*wheel_radius}"/>
</inertial>
</link>

Expand Down Expand Up @@ -107,9 +107,9 @@
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
<mass value="${wheel_mass}"/>
<inertia
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
ixx="${wheel_mass / 12.0 * (3*wheel_radius*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
iyy="${wheel_mass / 12.0 * (3*wheel_radius*wheel_radius + wheel_len*wheel_len)}" iyz="0.0"
izz="${wheel_mass / 2.0 * wheel_radius*wheel_radius}"/>
</inertial>
</link>

Expand Down

0 comments on commit ef3f9c6

Please sign in to comment.