diff --git a/scout_base/include/scout_base/scout_messenger.hpp b/scout_base/include/scout_base/scout_messenger.hpp
index a8111dd..05a70c9 100644
--- a/scout_base/include/scout_base/scout_messenger.hpp
+++ b/scout_base/include/scout_base/scout_messenger.hpp
@@ -161,8 +161,8 @@ class ScoutMessenger {
lateral_speed = 0;
}
- double d_x = linear_speed * std::cos(theta_) * dt;
- double d_y = (linear_speed * std::sin(theta_) + lateral_speed) * dt;
+ double d_x = (linear_speed * std::cos(theta_) - lateral_speed * std::sin(theta_)) * dt;
+ double d_y = (linear_speed * std::sin(theta_) + lateral_speed * std::cos(theta_)) * dt;
double d_theta = angular_speed * dt;
position_x_ += d_x;
diff --git a/scout_base/launch/scout_mini_omni_base.launch b/scout_base/launch/scout_mini_omni_base.launch
index e3c1362..48d2b5d 100644
--- a/scout_base/launch/scout_mini_omni_base.launch
+++ b/scout_base/launch/scout_mini_omni_base.launch
@@ -15,7 +15,7 @@
-
+
diff --git a/scout_bringup/launch/scout_mini_minimal.launch b/scout_bringup/launch/scout_mini_minimal.launch
index 418634d..6cbbeaa 100644
--- a/scout_bringup/launch/scout_mini_minimal.launch
+++ b/scout_bringup/launch/scout_mini_minimal.launch
@@ -4,7 +4,7 @@
-
+
diff --git a/scout_bringup/launch/scout_mini_omni_minimal.launch b/scout_bringup/launch/scout_mini_omni_minimal.launch
index 6bb83f9..62d9ed8 100644
--- a/scout_bringup/launch/scout_mini_omni_minimal.launch
+++ b/scout_bringup/launch/scout_mini_omni_minimal.launch
@@ -4,7 +4,7 @@
-
+