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