From c00601ade87648683a8f1e65cc36f7891db29325 Mon Sep 17 00:00:00 2001
From: Jaeyoung Lim <jalim@ethz.ch>
Date: Sat, 20 Aug 2022 16:28:45 +0200
Subject: [PATCH 1/2] Increase control authority of boats

---
 models/boat/boat.sdf.jinja | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/models/boat/boat.sdf.jinja b/models/boat/boat.sdf.jinja
index 92db9f5f64..cb33d59419 100644
--- a/models/boat/boat.sdf.jinja
+++ b/models/boat/boat.sdf.jinja
@@ -489,7 +489,7 @@
       <timeConstantUp>0.0125</timeConstantUp>
       <timeConstantDown>0.025</timeConstantDown>
       <maxRotVelocity>1100</maxRotVelocity>
-      <motorConstant>8.54858e-03</motorConstant>
+      <motorConstant>8.54858e-02</motorConstant>
       <momentConstant>0.01</momentConstant>
       <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
       <motorNumber>0</motorNumber>
@@ -506,7 +506,7 @@
       <timeConstantUp>0.0125</timeConstantUp>
       <timeConstantDown>0.025</timeConstantDown>
       <maxRotVelocity>1100</maxRotVelocity>
-      <motorConstant>8.54858e-03</motorConstant>
+      <motorConstant>8.54858e-02</motorConstant>
       <momentConstant>0.01</momentConstant>
       <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
       <motorNumber>1</motorNumber>

From 0ba0f34bce31970502dfedcc1601c9ff114ebd6e Mon Sep 17 00:00:00 2001
From: Jaeyoung Lim <jalim@ethz.ch>
Date: Sun, 21 Aug 2022 15:29:16 +0200
Subject: [PATCH 2/2] More directional stability on the dynamics

---
 models/boat/boat.sdf.jinja | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/models/boat/boat.sdf.jinja b/models/boat/boat.sdf.jinja
index cb33d59419..c58f65fe55 100644
--- a/models/boat/boat.sdf.jinja
+++ b/models/boat/boat.sdf.jinja
@@ -524,7 +524,7 @@
       <nDotR>0.0</nDotR>
       <xU>51.3</xU>
       <xUU>72.4</xUU>
-      <yV>40.0</yV>
+      <yV>102.6</yV>
       <yVV>0.0</yVV>
       <zW>500.0</zW>
       <kP>50.0</kP>