From ce7497d894114ed9fd796829caa7b696c112c072 Mon Sep 17 00:00:00 2001
From: luis-camero <88782189+luis-camero@users.noreply.github.com>
Date: Mon, 16 Oct 2023 15:55:27 -0400
Subject: [PATCH] [DiffBot] Inertia fix (#373)
---
.../diffbot/urdf/diffbot_description.urdf.xacro | 12 ++++++------
1 file changed, 6 insertions(+), 6 deletions(-)
diff --git a/ros2_control_demo_description/diffbot/urdf/diffbot_description.urdf.xacro b/ros2_control_demo_description/diffbot/urdf/diffbot_description.urdf.xacro
index 03aa3497f..263be605e 100644
--- a/ros2_control_demo_description/diffbot/urdf/diffbot_description.urdf.xacro
+++ b/ros2_control_demo_description/diffbot/urdf/diffbot_description.urdf.xacro
@@ -72,9 +72,9 @@
+ 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}"/>
@@ -107,9 +107,9 @@
+ 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}"/>