Autonomous Racing  1
f1tenth Project Group of Technical University Dortmund, Germany
parameters_q_learning.py
Go to the documentation of this file.
1 import torch
2 import torch.nn as nn
3 import torch.nn.functional as F
4 from torch.autograd import Variable
5 
6 import os
7 import rospy
8 
9 from rospkg import RosPack
10 
11 # General parameters
12 ACTIONS = [(-0.6, 0.2), (0.6, 0.2), (0, 0.2)]
13 ACTION_COUNT = len(ACTIONS)
14 
15 # Only use some of the LIDAR measurements
16 # When changing this value, also update laser_sample_count in q_learning.launch
17 LASER_SAMPLE_COUNT = 8
18 
19 
20 MODEL_FILENAME = os.path.join(RosPack().get_path(
21  "reinforcement_learning"), "q_learning.to")
22 
23 # Training parameters
24 
25 # Start by loading previously trained parameters.
26 # If this is False, training will start from scratch
27 CONTINUE = False
28 
29 DISCOUNT_FACTOR = 0.99 # aka gamma
30 
31 MAX_EPISODE_LENGTH = 500
32 # Sample neural net update batch from the replay memory.
33 # It contains this many steps.
34 MEMORY_SIZE = 5000
35 
36 BATCH_SIZE = 128
37 LEARNING_RATE = 0.0001
38 
39 # Probability to select a random episode starts at EPS_START
40 # and reaches EPS_END once EPS_DECAY episodes are completed.
41 EPS_START = 1.0
42 EPS_END = 0.3
43 EPS_DECAY = 10000
44 
45 
46 class NeuralQEstimator(nn.Module):
47  def __init__(self):
48  super(NeuralQEstimator, self).__init__()
49  self.fc1 = nn.Linear(LASER_SAMPLE_COUNT, 64)
50  self.fc2 = nn.Linear(64, 32)
51  self.fc3 = nn.Linear(32, ACTION_COUNT)
52 
53  def forward(self, x):
54  x = F.relu(self.fc1(x))
55  x = F.relu(self.fc2(x))
56  return self.fc3(x)
57 
58  def load(self):
59  self.load_state_dict(torch.load(MODEL_FILENAME))
60  rospy.loginfo("Model parameters loaded.")
61 
62  def save(self):
63  torch.save(self.state_dict(), MODEL_FILENAME)