Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Species exploration #94

Open
wants to merge 7 commits into
base: development
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion experiments/brain-speciation/manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
from pyrevolve.genotype.plasticoding import PlasticodingConfig
from pyrevolve.genotype.lsystem_neat.lsystem_neat_genotype import LSystemCPGHyperNEATGenotype, LSystemCPGHyperNEATGenotypeConfig
from pyrevolve.genotype.neat_brain_genome.neat_brain_genome import NeatBrainGenomeConfig
from .MorphologyCompatibility import MorphologyCompatibility
from pyrevolve.revolve_bot.morphology_compatibility import MorphologyCompatibility

from typing import TYPE_CHECKING
if TYPE_CHECKING:
Expand Down
248 changes: 248 additions & 0 deletions experiments/species_exploration/manager.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,248 @@
#!/usr/bin/env python3
from __future__ import annotations

from pyrevolve import parser
from pyrevolve.evolution import fitness
from pyrevolve.evolution.population.population_management import steady_state_population_management
from pyrevolve.evolution.selection import multiple_selection_with_duplicates, multiple_selection, tournament_selection
from pyrevolve.evolution.speciation.population_speciated import PopulationSpeciated
from pyrevolve.evolution.speciation.population_speciated_config import PopulationSpeciatedConfig
from pyrevolve.evolution.speciation.population_speciated_management import steady_state_speciated_population_management
from pyrevolve.experiment_management import ExperimentManagement
from pyrevolve.genotype.lsystem_neat.crossover import CrossoverConfig as lCrossoverConfig
from pyrevolve.genotype.lsystem_neat.crossover import standard_crossover as lcrossover
from pyrevolve.genotype.lsystem_neat.mutation import LSystemNeatMutationConf as lMutationConfig
from pyrevolve.genotype.plasticoding.mutation.mutation import MutationConfig as plasticMutationConfig
from pyrevolve.genotype.lsystem_neat.mutation import standard_mutation as lmutation
from pyrevolve.util.supervisor.analyzer_queue import AnalyzerQueue
from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue
from pyrevolve.custom_logging.logger import logger
from pyrevolve.genotype.plasticoding import PlasticodingConfig
from pyrevolve.genotype.lsystem_neat.lsystem_neat_genotype import LSystemCPGHyperNEATGenotype, LSystemCPGHyperNEATGenotypeConfig
from pyrevolve.genotype.neat_brain_genome.neat_brain_genome import NeatBrainGenomeConfig
from pyrevolve.revolve_bot.morphology_compatibility import MorphologyCompatibility

from typing import TYPE_CHECKING
if TYPE_CHECKING:
from typing import Union
from pyrevolve.evolution.population.population import Population
from pyrevolve.evolution.individual import Individual


async def run():
"""
The main coroutine, which is started below.
"""

# experiment params #
num_generations = 200
population_size = 100
offspring_size = 50
remove_species_gen_n = 100

body_conf = PlasticodingConfig(
max_structural_modules=20,
allow_vertical_brick=False,
use_movement_commands=True,
use_rotation_commands=False,
use_movement_stack=False,
allow_joint_joint_attachment=False,
)
brain_conf = NeatBrainGenomeConfig()
brain_conf.multineat_params.DisjointCoeff = 0.3
brain_conf.multineat_params.ExcessCoeff = 0.3
brain_conf.multineat_params.WeightDiffCoeff = 0.3
brain_conf.multineat_params.ActivationADiffCoeff = 0.3
brain_conf.multineat_params.ActivationBDiffCoeff = 0.3
brain_conf.multineat_params.TimeConstantDiffCoeff = 0.3
brain_conf.multineat_params.BiasDiffCoeff = 0.3
brain_conf.multineat_params.ActivationFunctionDiffCoeff = 0.3
brain_conf.multineat_params.CompatTreshold = 3.0
brain_conf.multineat_params.MinCompatTreshold = 3.0
brain_conf.multineat_params.CompatTresholdModifier = 0.1
brain_conf.multineat_params.CompatTreshChangeInterval_Generations = 1
brain_conf.multineat_params.CompatTreshChangeInterval_Evaluations = 1
genotype_conf = LSystemCPGHyperNEATGenotypeConfig(body_conf, brain_conf)

plasticMutation_conf = plasticMutationConfig(
mutation_prob=0.8,
genotype_conf=body_conf
)

lmutation_conf = lMutationConfig(
plasticoding_mutation_conf=plasticMutation_conf,
neat_conf=brain_conf,
)

crossover_conf = lCrossoverConfig(
crossover_prob=0.8,
)

compatibitity_tester = MorphologyCompatibility(
total_threshold=1.0,
size=1.0,
brick_count=1.0,
proportion=1.0,
coverage=1.0,
joints=1.5,
branching=1.0,
symmetry=0.0,
max_permitted_modules=body_conf.max_structural_modules,
)

# experiment params #

# Parse command line / file input arguments
args = parser.parse_args()
experiment_management = ExperimentManagement(args)
has_offspring = False
do_recovery = args.recovery_enabled and not experiment_management.experiment_is_new()

logger.info(f'Activated run {args.run} of experiment {args.experiment_name}')

species_done = False
if do_recovery:
#TODO actually, if gen_num > remove_species_gen_n, we should read the recovery state with species=False
gen_num, has_offspring, next_robot_id, next_species_id = \
experiment_management.read_recovery_state(population_size, offspring_size, species=True)
# Partial recovery for speciated populations is not implemented
has_offspring = False
if gen_num == remove_species_gen_n:
new_gen_num, new_has_offspring, new_next_robot_id, _ = \
experiment_management.read_recovery_state(population_size, offspring_size, species=False)
if new_gen_num > gen_num:
species_done = True
gen_num = new_gen_num
has_offspring = new_has_offspring
next_robot_id = new_next_robot_id

if gen_num == num_generations-1:
logger.info('Experiment is already complete.')
return
else:
gen_num = 0
next_robot_id = 1
next_species_id = 1

if gen_num < 0:
logger.info('Experiment continuing from first generation')
gen_num = 0

if next_robot_id < 0:
next_robot_id = 1

if next_species_id < 0:
next_species_id = 1

def are_individuals_brains_compatible_fn(individual1: Individual,
individual2: Individual) -> bool:
assert isinstance(individual1.genotype, LSystemCPGHyperNEATGenotype)
assert isinstance(individual2.genotype, LSystemCPGHyperNEATGenotype)
return individual1.genotype.is_brain_compatible(individual2.genotype, genotype_conf)

def are_individuals_morphologies_compatible_fn(individual1: Individual,
individual2: Individual) -> bool:
return compatibitity_tester.compatible_individuals(individual1, individual2)

population_conf = PopulationSpeciatedConfig(
population_size=population_size,
genotype_constructor=LSystemCPGHyperNEATGenotype,
genotype_conf=genotype_conf,
fitness_function=fitness.displacement_velocity,
mutation_operator=lmutation,
mutation_conf=lmutation_conf,
crossover_operator=lcrossover,
crossover_conf=crossover_conf,
selection=lambda individuals: tournament_selection(individuals, 2),
parent_selection=lambda individuals: multiple_selection_with_duplicates(individuals, 2, tournament_selection),
population_management=steady_state_speciated_population_management,
population_management_selector=tournament_selection,
evaluation_time=args.evaluation_time,
offspring_size=offspring_size,
experiment_name=args.experiment_name,
experiment_management=experiment_management,
# species stuff
# are_individuals_compatible_fn=are_individuals_brains_compatible_fn,
are_individuals_compatible_fn=are_individuals_morphologies_compatible_fn,
young_age_threshold=5,
young_age_fitness_boost=2.0,
old_age_threshold=35,
old_age_fitness_penalty=0.5,
species_max_stagnation=30,
)

def adapt_population_config(config):
config.population_management = steady_state_population_management
config.parent_selection = \
lambda individuals: multiple_selection(individuals, 2, tournament_selection)

n_cores = args.n_cores

simulator_queue = SimulatorQueue(n_cores, args, args.port_start)
await simulator_queue.start()

analyzer_queue = AnalyzerQueue(1, args, args.port_start+n_cores)
await analyzer_queue.start()

population: Union[PopulationSpeciated, Population]
if not species_done:
population = PopulationSpeciated(population_conf,
simulator_queue,
analyzer_queue,
next_robot_id,
next_species_id)
else:
population = \
Population(population_conf,
simulator_queue,
analyzer_queue,
next_robot_id)
adapt_population_config(population.config)

if do_recovery:
# loading a previous state of the experiment
population.load_snapshot(gen_num)
if gen_num >= 0:
logger.info(f'Recovered snapshot {gen_num}, pop with {len(population.genus)} individuals')

# TODO partial recovery is not implemented, this is a substitute
next_robot_id = 1 + population.config.population_size + gen_num * population.config.offspring_size
population.next_robot_id = next_robot_id

if has_offspring:
if not species_done:
raise NotImplementedError('partial recovery not implemented')
recovered_individuals = population.load_partially_completed_generation(gen_num, population_size, offspring_size, next_robot_id)
gen_num += 1
logger.info(f'Recovered unfinished offspring for generation {gen_num}')

if gen_num == 0:
await population.initialize(recovered_individuals)
else:
population = await population.next_generation(gen_num, recovered_individuals)

experiment_management.export_snapshots_species(population.genus, gen_num)
else:
# starting a new experiment
experiment_management.create_exp_folders()
await population.initialize()
experiment_management.export_snapshots_species(population.genus, gen_num)

while gen_num < num_generations-1:
gen_num += 1
population = await population.next_generation(gen_num)
if isinstance(population, PopulationSpeciated):
assert not species_done
experiment_management.export_snapshots_species(population.genus, gen_num)
else:
assert species_done
# WARNING: This export_snapshots may need fixing
experiment_management.export_snapshots(population.individuals, gen_num)

if gen_num == remove_species_gen_n:
species_done = True
population = population.into_population()
# Adjust the configuration
adapt_population_config(population.config)
# save the converted population for debugging (may create unpredictable behaviours in recovery)
experiment_management.export_snapshots(population.individuals, f"{gen_num}_flattened")
64 changes: 55 additions & 9 deletions pyrevolve/evolution/population/population.py
Original file line number Diff line number Diff line change
@@ -1,17 +1,19 @@
from __future__ import annotations
import asyncio
import os
import re

from pyrevolve.evolution.individual import Individual
from pyrevolve.custom_logging.logger import logger
from pyrevolve.evolution.population.population_config import PopulationConfig

from typing import TYPE_CHECKING
if TYPE_CHECKING:
from typing import List, Optional
from typing import List, Optional, Callable
from pyrevolve.evolution.speciation.species import Species
from pyrevolve.tol.manage.measures import BehaviouralMeasurements
from pyrevolve.util.supervisor.analyzer_queue import AnalyzerQueue, SimulatorQueue
from pyrevolve.evolution.speciation.population_speciated import PopulationSpeciated, PopulationSpeciatedConfig


class Population:
Expand Down Expand Up @@ -63,14 +65,16 @@ def _new_individual(self,

def load_snapshot(self, gen_num: int) -> None:
"""
Recovers all genotypes and fitnesses of robots in the lastest selected population
Recovers all genotypes and fitnesses of robots in the selected generation
:param gen_num: number of the generation snapshot to recover
"""
data_path = self.config.experiment_management.experiment_folder
for r, d, f in os.walk(os.path.join(data_path, f'selectedpop_{gen_num}')):
for file in f:
if 'body' in file:
_id = file.split('.')[0].split('_')[-2]+'_'+file.split('.')[0].split('_')[-1]
extract_id = re.compile(r'^body_(\d+)\.png$')
generation_folder = self.config.experiment_management.generation_folder(gen_num)
for _, _, files in os.walk(generation_folder):
for file in files:
test = extract_id.search(file)
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

test?

if test is not None:
_id = test.group(1)
self.individuals.append(
self.config.experiment_management.load_individual(_id, self.config))

Expand All @@ -95,9 +99,8 @@ def load_offspring(self,
n_robots = population_size + last_snapshot * offspring_size

for robot_id in range(n_robots+1, next_robot_id):
#TODO refactor filename
individuals.append(
self.config.experiment_management.load_individual(str(robot_id), self.config)
self.config.experiment_management.load_individual(robot_id, self.config)
)

self.next_robot_id = next_robot_id
Expand Down Expand Up @@ -172,6 +175,49 @@ async def next_generation(self,

return new_population

def into_speciated_population(self,
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

get_speciated_population?

are_individuals_compatible_fn: Optional[Callable[[Individual, Individual], bool]] = None,
young_age_threshold: int = None,
young_age_fitness_boost: float = None,
old_age_threshold: int = None,
old_age_fitness_penalty: float = None,
species_max_stagnation: int = None) -> PopulationSpeciated:
"""
Creates species based on the current population.

You have to populate the missing parameter for the PopulationSpeciatedConfig in case the
`self.config` is not already of type PopulationSpeciatedConfig

:param are_individuals_compatible_fn: see PopulationSpeciatedConfig
:param young_age_threshold: see PopulationSpeciatedConfig
:param young_age_fitness_boost: see PopulationSpeciatedConfig
:param old_age_threshold: see PopulationSpeciatedConfig
:param old_age_fitness_penalty: see PopulationSpeciatedConfig
:param species_max_stagnation: see PopulationSpeciatedConfig
:return: A new version of the current population, but divided in species.
"""
from pyrevolve.evolution.speciation.population_speciated import PopulationSpeciated, PopulationSpeciatedConfig
young_age_threshold = PopulationSpeciatedConfig.DEFAULT_YOUNG_AGE_THRESHOLD if young_age_threshold is None else young_age_threshold
young_age_fitness_boost = PopulationSpeciatedConfig.DEFAULT_YOUNG_AGE_FITNESS_BOOST if young_age_fitness_boost is None else young_age_fitness_boost
old_age_threshold = PopulationSpeciatedConfig.DEFAULT_OLD_AGE_THRESHOLD if old_age_threshold is None else old_age_threshold
old_age_fitness_penalty = PopulationSpeciatedConfig.DEFAULT_OLD_AGE_FITNESS_PENALTY if old_age_fitness_penalty is None else old_age_fitness_penalty
species_max_stagnation = PopulationSpeciatedConfig.DEFAULT_SPECIES_MAX_STAGNATION if species_max_stagnation is None else species_max_stagnation

new_population_config = PopulationSpeciatedConfig \
.from_population_config(self.config,
are_individuals_compatible_fn=are_individuals_compatible_fn,
young_age_threshold=young_age_threshold,
young_age_fitness_boost=young_age_fitness_boost,
old_age_threshold=old_age_threshold,
old_age_fitness_penalty=old_age_fitness_penalty,
species_max_stagnation=species_max_stagnation,)
new_population = PopulationSpeciated(new_population_config,
self.simulator_queue,
self.analyzer_queue,
self.next_robot_id)
new_population.genus.speciate(self.individuals)
return new_population

async def evaluate(self,
new_individuals: List[Individual],
gen_num: int,
Expand Down
6 changes: 6 additions & 0 deletions pyrevolve/evolution/speciation/population_speciated.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ def __init__(self,
next_species_id: int = 1):
# TODO analyzer
super().__init__(config, simulator_queue, analyzer_queue, next_robot_id)
self.config: PopulationSpeciatedConfig = self.config # this is only for correct type hinting
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Too bad we have to do it this way...

self.individuals = None # TODO Crash when we should use it

# Genus contains the collection of different species.
Expand Down Expand Up @@ -82,6 +83,11 @@ async def next_generation(self,

return new_population

def into_population(self) -> Population:
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Into population is a weird name to me for a function.

Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe get_regular_population?

new_population = Population(self.config, self.simulator_queue, self.analyzer_queue, self.next_robot_id)
new_population.individuals = [individual for individual in self.genus.iter_individuals()]
return new_population

def _generate_individual(self, individuals: List[Individual]) -> Individual:
# Selection operator (based on fitness)
# Crossover
Expand Down
Loading