Skip to content

Commit

Permalink
Save individuals on disc, Added option to continue training
Browse files Browse the repository at this point in the history
  • Loading branch information
StefanJVA authored and unknown committed Sep 16, 2019
1 parent b499244 commit a9638d5
Show file tree
Hide file tree
Showing 2 changed files with 38 additions and 14 deletions.
17 changes: 10 additions & 7 deletions ros_ws/src/autonomous/evolutionary/scripts/neural_car_driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,13 @@
POPULATION_SIZE = 10
SURVIVOR_COUNT = 4

LEARN_RATE = 0.2
LEARN_RATE = 0.1
normal_distribution = torch.distributions.normal.Normal(0, LEARN_RATE)

MODEL_FILENAME = os.path.join(
RosPack().get_path("evolutionary"),
"evolutionary.to")
"evolutionary")
MODEL_FILENAME_ENDING = ".to"

drive_parameters_publisher = rospy.Publisher(
TOPIC_DRIVE_PARAMETERS, drive_param, queue_size=1)
Expand Down Expand Up @@ -98,20 +99,22 @@ def mutate(self):
offspring.load_vector(parameters)
return offspring

def load(self):
self.load_state_dict(torch.load(MODEL_FILENAME))
def load(self, index):
self.load_state_dict(torch.load(
MODEL_FILENAME + "_" + str(index) + MODEL_FILENAME_ENDING))
rospy.loginfo("Model parameters loaded.")

def save(self):
torch.save(self.state_dict(), MODEL_FILENAME)
def save(self, index):
torch.save(self.state_dict(), MODEL_FILENAME +
"_" + str(index) + MODEL_FILENAME_ENDING)


if __name__ == '__main__':
rospy.init_node('evolutionary_driver', anonymous=True)
driver = NeuralCarDriver()

try:
driver.load()
driver.load(0)
except IOError:
message = "Model parameters for the neural net not found. You need to train it first."
rospy.logerr(message)
Expand Down
35 changes: 28 additions & 7 deletions ros_ws/src/autonomous/evolutionary/scripts/train.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,10 @@
from neural_car_driver import *
import simulation_tools.reset_car as reset_car

MAX_EPISODE_LENGTH = 5000
INITIAL_RANDOM_GENERATIONS = 20
CONTINUE_TRAINING = True


class TrainingNode():
def __init__(self):
Expand All @@ -18,15 +22,24 @@ def __init__(self):
rospy.Subscriber(TOPIC_CRASH, Empty, self.on_crash)

self.population = []
self.untested_population = [NeuralCarDriver()
for _ in range(POPULATION_SIZE)]
self.current_driver = self.untested_population[0]

self.is_terminal_step = False
self.episode_length = 0
self.generation = 0
self.test = 0

self.untested_population = []
if CONTINUE_TRAINING:
for i in range(POPULATION_SIZE):
individuum = NeuralCarDriver()
individuum.load(i)
self.untested_population.append(individuum)
else:
self.untested_population = [NeuralCarDriver()
for _ in range(POPULATION_SIZE)]

self.current_driver = self.untested_population[0]

def on_receive_laser_scan(self, message):
self.current_driver.drive(message)
self.episode_length += 1
Expand Down Expand Up @@ -56,17 +69,25 @@ def on_complete_test(self):

def on_complete_generation(self):
self.population.sort(key=lambda driver: driver.fitness, reverse=True)
self.population[0].save()
rospy.loginfo("Generation {:d}: Fitness of the population: {:s}".format(

for i in range(POPULATION_SIZE):
self.population[i].save(i)

rospy.loginfo("{:s}Generation {:d}: Fitness of the population: {:s}".format(
"(Random) " if self.generation < INITIAL_RANDOM_GENERATIONS else "",
self.generation + 1,
", ".join(str(driver.fitness) for driver in self.population)
))
self.population = self.population[:SURVIVOR_COUNT]

self.untested_population = list()
for _ in range(POPULATION_SIZE - SURVIVOR_COUNT):
parent = random.choice(self.population)
offspring = parent.mutate()
offspring = None
if self.generation < INITIAL_RANDOM_GENERATIONS:
offspring = NeuralCarDriver()
else:
parent = random.choice(self.population)
offspring = parent.mutate()
self.untested_population.append(offspring)

self.current_driver = self.untested_population[0]
Expand Down

0 comments on commit a9638d5

Please sign in to comment.