diff --git a/src/odroid/catkin_ws/src/car/include/laneDetection/EdgeDetection.hpp b/src/odroid/catkin_ws/src/car/include/laneDetection/EdgeDetection.hpp
index 5fd0e46e963bb3b6d91cb74a65723b57b5f102bc..f39138b79021e25be692a70d2b62c699d1e5498c 100644
--- a/src/odroid/catkin_ws/src/car/include/laneDetection/EdgeDetection.hpp
+++ b/src/odroid/catkin_ws/src/car/include/laneDetection/EdgeDetection.hpp
@@ -25,7 +25,7 @@ private:
 
     // parameters for canny edge detection
     // recommended a upper:lower ratio between 2:1 and 3:1
-    int low_threshold = 120; // 100 ->img22, 50 -> img 20 // lower threshold leads to more noises; test_mp4 reveals noise on the track
+    int low_threshold = 130; // 100 ->img22, 50 -> img 20 // lower threshold leads to more noises; test_mp4 reveals noise on the track
     double canny_ratio = 3;
     int kernel_size = 3;
 
diff --git a/src/odroid/catkin_ws/src/car/src/laneDetection/EdgeDetection.cpp b/src/odroid/catkin_ws/src/car/src/laneDetection/EdgeDetection.cpp
index d3a0baf064602f0b70e8fd2c4bac6d8867f82fce..831a04f60483ae2cf0bdf4e63ea6d2a1698c987e 100644
--- a/src/odroid/catkin_ws/src/car/src/laneDetection/EdgeDetection.cpp
+++ b/src/odroid/catkin_ws/src/car/src/laneDetection/EdgeDetection.cpp
@@ -419,20 +419,20 @@ void EdgeDetection::calculateSpeedAngle() {
             speed = 0.5;
             break;
         case 5 :
-            angle = 17.5;
+            angle = 15.0;
             speed = 0.5;
             break;
         case 6 :
-            angle = 20.0;
+            angle = 15.0;
             speed = 0.5;
             break;
         case 7 :
-            angle = 23;
+            angle = 15.5;
             speed = 0.5;
             break;
         case 8 :
-            angle = 25;
-            speed = 0.3;
+            angle = 17.5;
+            speed = 0.5;
             break;
 
             // LEFT TURN
@@ -455,11 +455,11 @@ void EdgeDetection::calculateSpeedAngle() {
             angle = -23.5;
             break;
         case -7 :
-            angle = -23.5;
+            angle = -15.5;
             break;
         case -8 :
-            angle = -25;
-            speed = 0.3;
+            angle = -17.5;
+            speed = 0.5;
             break;
 
         default: