Autonomous Racing  1
f1tenth Project Group of Technical University Dortmund, Germany
drive_q_learning.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from reinforcement_learning_node import ReinforcementLearningNode, device
4 import os
5 import rospy
6 from parameters_q_learning import NeuralQEstimator, ACTIONS, LASER_SAMPLE_COUNT
7 import torch
8 
9 
11  ''' ROS node to drive the car using previously learned
12  Q-Learning weights
13  '''
14 
15  def __init__(self):
16  self.policy = NeuralQEstimator().to(device)
17 
18  try:
19  self.policy.load()
20  self.policy.eval()
21  except IOError:
22  message = "Model parameters for the neural net not found. You need to train it first."
23  rospy.logerr(message)
24  rospy.signal_shutdown(message)
25  exit(1)
26 
27  ReinforcementLearningNode.__init__(self, ACTIONS, LASER_SAMPLE_COUNT)
28 
29  def on_receive_laser_scan(self, message):
30  if self.policy is None:
31  return
32 
33  state = self.convert_laser_message_to_tensor(message)
34 
35  with torch.no_grad():
36  action = self.policy(state).max(0)[1].item()
37  self.perform_action(action)
38 
39 
40 rospy.init_node('q_learning_driving', anonymous=True)
42 rospy.spin()
def convert_laser_message_to_tensor(self, message, use_device=True)