From 575ca4eb03ac8bfdcb51efbcf6b5977fe0952d76 Mon Sep 17 00:00:00 2001
From: Farid Alijani <farid.alijani@student.lut.fi>
Date: Thu, 19 May 2016 21:40:11 +0200
Subject: [PATCH] RL and PID modified

---
 .../docking_with_q_learning/src/RL_Docking.cpp         |  2 +-
 .../docking_with_q_learning/src/RL_Docking.cpp~        | 10 +++++-----
 2 files changed, 6 insertions(+), 6 deletions(-)

diff --git a/MobileRobot/Machine_Learning/RL4Docking/docking_with_q_learning/src/RL_Docking.cpp b/MobileRobot/Machine_Learning/RL4Docking/docking_with_q_learning/src/RL_Docking.cpp
index 9a99ca7b..821cd9bd 100644
--- a/MobileRobot/Machine_Learning/RL4Docking/docking_with_q_learning/src/RL_Docking.cpp
+++ b/MobileRobot/Machine_Learning/RL4Docking/docking_with_q_learning/src/RL_Docking.cpp
@@ -109,7 +109,7 @@ double RL4Docking::Q_next_state;
 double RL4Docking::reward;
 int RL4Docking::counter = 0;
 int RL4Docking::Time_Reward;
-int RL4Docking::iterations = 20;
+int RL4Docking::iterations = 50;
 double RL4Docking::sample;
 
 int RL4Docking::i_Goal = 20; // right now it has been set manually
diff --git a/MobileRobot/Machine_Learning/RL4Docking/docking_with_q_learning/src/RL_Docking.cpp~ b/MobileRobot/Machine_Learning/RL4Docking/docking_with_q_learning/src/RL_Docking.cpp~
index f40fa4fd..9a99ca7b 100644
--- a/MobileRobot/Machine_Learning/RL4Docking/docking_with_q_learning/src/RL_Docking.cpp~
+++ b/MobileRobot/Machine_Learning/RL4Docking/docking_with_q_learning/src/RL_Docking.cpp~
@@ -13,7 +13,6 @@
 #include <aruco/cvdrawingutils.h>
 
 #include "ros/ros.h"
-
 #include <tf/transform_broadcaster.h>
 #include <tf/transform_listener.h>
 #include <tf/tf.h>
@@ -78,7 +77,8 @@ float RL4Docking::closestRangeF;
 //const double RL4Docking::RefPose[4] = {-.0957, 0.00638817 /* Y_ref*/ ,  0.308857 /* X_ref*/ , 0.17 /* theta_ref*/}; 
 
 // ---- Ref. Values for Logitech Camera ---- //
-const double RL4Docking::RefPose[4] = {-.0957, -0.0305812 /* Y_ref*/ ,  0.265274 /* X_ref*/ , -0.535004 /* theta_ref*/}; 
+const double RL4Docking::RefPose[4] = {-.0957, -0.0305812 /* Y_ref*/ ,  0.26814 /* X_ref*/ , -0.553234 /* theta_ref*/}; 
+
 
 // random pose initialized
 const double RL4Docking::y_up = .24; 
@@ -109,7 +109,7 @@ double RL4Docking::Q_next_state;
 double RL4Docking::reward;
 int RL4Docking::counter = 0;
 int RL4Docking::Time_Reward;
-int RL4Docking::iterations = 30;
+int RL4Docking::iterations = 20;
 double RL4Docking::sample;
 
 int RL4Docking::i_Goal = 20; // right now it has been set manually
@@ -126,7 +126,7 @@ double RL4Docking::x_thresh_dock = .001;
 double RL4Docking::y_thresh_dock = .002;
 double RL4Docking::theta_thresh_dock = (CV_PI/180) * 3; // 1 deg.
 
-double RL4Docking::safety_margin_X = .13; // safety margin X axis in docking process : 14.5 cm
+double RL4Docking::safety_margin_X = .145; // safety margin X axis in docking process : 14.5 cm
 
 // ------ offsets X, Y, theta for Undocking ---------
 double RL4Docking::x_thresh_undock = .02;
@@ -946,7 +946,7 @@ void RL4Docking::GenRandVal()
 	theta_dot = ((double) rand() / (RAND_MAX)) * (.1 - (-.1)) + (-.1);	// -.1 < theta_dot < .1
 	
 	// ------------------ Generating Random Pose ------------------
-	x_new = ((double) rand() / (RAND_MAX)) * (1.1 - (2*safety_margin_X)) + (2*safety_margin_X);
+	x_new = ((double) rand() / (RAND_MAX)) * (1.1 - (4*safety_margin_X)) + (4*safety_margin_X);
 	//x_new = 1.05;
 	y_new = ((double) rand() / (RAND_MAX)) * (y_up - y_dwn) + y_dwn;
 	//theta_new = ((double) rand() / (RAND_MAX)) * (theta_up - theta_dwn) + theta_dwn; 
-- 
GitLab