Skip to content

Commit ce7497d

Browse files
authored
[DiffBot] Inertia fix (ros-controls#373)
1 parent 7a5cf6d commit ce7497d

File tree

1 file changed

+6
-6
lines changed

1 file changed

+6
-6
lines changed

ros2_control_demo_description/diffbot/urdf/diffbot_description.urdf.xacro

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -72,9 +72,9 @@
7272
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
7373
<mass value="${wheel_mass}"/>
7474
<inertia
75-
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
76-
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
77-
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
75+
ixx="${wheel_mass / 12.0 * (3*wheel_radius*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
76+
iyy="${wheel_mass / 12.0 * (3*wheel_radius*wheel_radius + wheel_len*wheel_len)}" iyz="0.0"
77+
izz="${wheel_mass / 2.0 * wheel_radius*wheel_radius}"/>
7878
</inertial>
7979
</link>
8080

@@ -107,9 +107,9 @@
107107
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
108108
<mass value="${wheel_mass}"/>
109109
<inertia
110-
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
111-
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
112-
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
110+
ixx="${wheel_mass / 12.0 * (3*wheel_radius*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
111+
iyy="${wheel_mass / 12.0 * (3*wheel_radius*wheel_radius + wheel_len*wheel_len)}" iyz="0.0"
112+
izz="${wheel_mass / 2.0 * wheel_radius*wheel_radius}"/>
113113
</inertial>
114114
</link>
115115

0 commit comments

Comments
 (0)