Autonomous Racing  1
f1tenth Project Group of Technical University Dortmund, Germany
parameters_policy_gradient.py
Go to the documentation of this file.
1 import torch
2 import torch.nn as nn
3 
4 import os
5 import rospy
6 
7 from rospkg import RosPack
8 
9 ACTIONS = [(-0.8, 0.1), (0.8, 0.1), (0.5, 0.2),
10  (-0.5, 0.2), (0, 0.2), (0, 0.4)]
11 ACTION_COUNT = len(ACTIONS)
12 
13 # Only use some of the LIDAR measurements
14 # When changing this value, also update laser_sample_count in
15 # policy_gradient.launch
16 LASER_SAMPLE_COUNT = 8
17 
18 MODEL_FILENAME = os.path.join(RosPack().get_path(
19  "reinforcement_learning"), "policy_gradient.to")
20 
21 # Start by loading previously trained parameters.
22 # If this is False, training will start from scratch
23 CONTINUE = False
24 
25 DISCOUNT_FACTOR = 0.99 # aka gamma
26 
27 MAX_EPISODE_LENGTH = 5000
28 
29 LEARNING_RATE = 0.001
30 
31 
32 class Policy(nn.Module):
33  def __init__(self):
34  super(Policy, self).__init__()
35 
36  self.layers = nn.Sequential(
37  nn.Linear(LASER_SAMPLE_COUNT, 32),
38  nn.ReLU(),
39  nn.Linear(32, 18),
40  nn.ReLU(),
41  nn.Linear(18, ACTION_COUNT),
42  nn.Softmax(dim=-1)
43  )
44 
45  def forward(self, x):
46  return self.layers.forward(x)
47 
48  def load(self):
49  if os.path.isfile(MODEL_FILENAME):
50  self.load_state_dict(torch.load(MODEL_FILENAME))
51  rospy.loginfo("Model parameters loaded.")
52 
53  def save(self):
54  torch.save(self.state_dict(), MODEL_FILENAME)