diff --git a/experiments/karines_experiments/check-experiments-status.sh b/experiments/karines_experiments/check-experiments-status.sh
index c0c71a0b97..3c99b22394 100755
--- a/experiments/karines_experiments/check-experiments-status.sh
+++ b/experiments/karines_experiments/check-experiments-status.sh
@@ -1,8 +1,8 @@
#!/bin/bash
-runs=10
-final_gen=149
-experiments=("hyperplasticodingseasons")
+runs=5
+final_gen=199
+experiments=("hyperplasticodingseasonsI15" "hyperplasticodingp" "hyperplasticodingt3")
for i in $(seq $runs)
diff --git a/experiments/karines_experiments/consolidate_experiments.py b/experiments/karines_experiments/consolidate_experiments.py
index 3cfdda4860..fe51e5ba92 100644
--- a/experiments/karines_experiments/consolidate_experiments.py
+++ b/experiments/karines_experiments/consolidate_experiments.py
@@ -8,17 +8,18 @@
dirpath = 'data/'
experiments_type = [
- 'hyperplasticodingt4',
-'hyperplasticodingoldt4',
-'hyperplasticodingoldt3'
+ #'hyperplasticodingp',
+ #'hyperplasticodingt3',
+ 'hyperplasticodingseasons'
+
]
environments = {
- 'hyperplasticodingt4': ['tilted4'],
- 'hyperplasticodingoldt4': ['tilted4'],
- 'hyperplasticodingoldt3': ['tilted3']
+ #'hyperplasticodingp': ['plane'],
+ #'hyperplasticodingt3': ['tilted3'],
+ 'hyperplasticodingseasons' : ['plane', 'tilted3']
}
-runs = range(1, 10+1)
+runs = range(1, 5+1)
# set these variables according to your experiments #
diff --git a/experiments/karines_experiments/hyperplasticodingp.py b/experiments/karines_experiments/hyperplasticodingp.py
new file mode 100644
index 0000000000..f95df81f7a
--- /dev/null
+++ b/experiments/karines_experiments/hyperplasticodingp.py
@@ -0,0 +1,174 @@
+#!/usr/bin/env python3
+import asyncio
+
+from pyrevolve import parser
+from pyrevolve.evolution import fitness
+from pyrevolve.evolution.selection import multiple_selection, tournament_selection
+from pyrevolve.evolution.population import Population, PopulationConfig
+from pyrevolve.evolution.pop_management.steady_state import steady_state_population_management
+from pyrevolve.experiment_management import ExperimentManagement
+from pyrevolve.genotype.hyperplasticoding_v2.crossover.crossover import CrossoverConfig
+from pyrevolve.genotype.hyperplasticoding_v2.crossover.standard_crossover import standard_crossover
+from pyrevolve.genotype.hyperplasticoding_v2.initialization import random_initialization
+from pyrevolve.genotype.hyperplasticoding_v2.mutation.mutation import MutationConfig
+from pyrevolve.genotype.hyperplasticoding_v2.mutation.standard_mutation import standard_mutation
+from pyrevolve.genotype.hyperplasticoding_v2.hyperplasticoding import HyperPlasticodingConfig
+from pyrevolve.tol.manage import measures
+from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue
+from pyrevolve.util.supervisor.analyzer_queue import AnalyzerQueue
+from pyrevolve.custom_logging.logger import logger
+import sys
+
+
+async def run():
+ """
+ The main coroutine, which is started below.
+ """
+
+ # experiment params #
+ num_generations = 200
+ population_size = 100
+ offspring_size = 100
+ front = 'none'
+
+ # environment world and z-start
+ environments = {'plane': 0.03 }
+
+ # calculation of the measures can be on or off, because they are expensive
+ novelty_on = {'novelty': False,
+ 'novelty_pop': True,
+ 'measures': ['branching',
+ 'limbs',
+ 'length_of_limbs',
+ 'coverage',
+ 'joints',
+ 'proportion',
+ 'size',
+ 'symmetry']
+ }
+
+ cppn_config_path = 'pyrevolve/genotype/hyperplasticoding_v2/config-nonplastic'
+
+ genotype_conf = HyperPlasticodingConfig(
+ plastic=False,
+ cppn_config_path=cppn_config_path
+ )
+
+ mutation_conf = MutationConfig(
+ mutation_prob=1,
+ genotype_conf=genotype_conf,
+ cppn_config_path=cppn_config_path
+ )
+
+ crossover_conf = CrossoverConfig(
+ crossover_prob=0,
+ cppn_config_path=cppn_config_path
+ )
+
+ # experiment params #
+
+ # Parse command line / file input arguments
+ settings = parser.parse_args()
+
+ experiment_management = ExperimentManagement(settings, environments)
+ do_recovery = settings.recovery_enabled and not experiment_management.experiment_is_new()
+
+
+ logger.info('Activated run '+settings.run+' of experiment '+settings.experiment_name)
+
+ if do_recovery:
+ gen_num, has_offspring, next_robot_id = experiment_management.read_recovery_state(population_size,
+ offspring_size)
+ if gen_num == num_generations-1:
+ logger.info('Experiment is already complete.')
+ return
+ else:
+ gen_num = 0
+ next_robot_id = 1
+
+ def fitness_function_plane(measures, robot):
+ return fitness.displacement_velocity_hill(measures, robot)
+
+ fitness_function = {'plane': fitness_function_plane}
+
+ population_conf = PopulationConfig(
+ population_size=population_size,
+ genotype_constructor=random_initialization,
+ genotype_conf=genotype_conf,
+ fitness_function=fitness_function,
+ mutation_operator=standard_mutation,
+ mutation_conf=mutation_conf,
+ crossover_operator=standard_crossover,
+ crossover_conf=crossover_conf,
+ selection=lambda individuals: tournament_selection(individuals, environments, 2),
+ parent_selection=lambda individuals: multiple_selection(individuals, 2, tournament_selection, environments),
+ population_management=steady_state_population_management,
+ population_management_selector=tournament_selection,
+ evaluation_time=settings.evaluation_time,
+ offspring_size=offspring_size,
+ experiment_name=settings.experiment_name,
+ experiment_management=experiment_management,
+ environments=environments,
+ novelty_on=novelty_on,
+ front=front,
+ run_simulation=settings.run_simulation,
+ all_settings=settings,
+ )
+
+ simulator_queue = {}
+ analyzer_queue = None
+
+ if settings.run_simulation == 1:
+ previous_port = None
+ for environment in environments:
+
+ settings.world = environment
+ settings.z_start = environments[environment]
+
+ if previous_port is None:
+ port = settings.port_start
+ previous_port = port
+ else:
+ port = previous_port+settings.n_cores
+ previous_port = port
+
+ simulator_queue[environment] = SimulatorQueue(settings.n_cores, settings, port)
+ await simulator_queue[environment].start()
+
+ analyzer_queue = AnalyzerQueue(1, settings, port+settings.n_cores)
+ await analyzer_queue.start()
+
+ population = Population(population_conf, simulator_queue, analyzer_queue, next_robot_id)
+
+ if do_recovery:
+
+ population.load_novelty_archive()
+
+ if gen_num >= 0:
+ # loading a previous state of the experiment
+ await population.load_snapshot(gen_num)
+ logger.info('Recovered snapshot '+str(gen_num)+', pop with ' + str(len(population.individuals))+' individuals')
+
+ if has_offspring:
+ individuals = await population.load_offspring(gen_num, population_size, offspring_size, next_robot_id)
+ gen_num += 1
+ logger.info('Recovered unfinished offspring '+str(gen_num))
+
+ if gen_num == 0:
+ await population.init_pop(individuals)
+ else:
+ population = await population.next_gen(gen_num, individuals)
+
+ experiment_management.export_snapshots(population.individuals, gen_num)
+ else:
+ # starting a new experiment
+ experiment_management.create_exp_folders()
+ await population.init_pop()
+ experiment_management.export_snapshots(population.individuals, gen_num)
+
+ while gen_num < num_generations-1:
+ gen_num += 1
+ population = await population.next_gen(gen_num)
+ experiment_management.export_snapshots(population.individuals, gen_num)
+
+ # output result after completing all generations...
\ No newline at end of file
diff --git a/experiments/karines_experiments/hyperplasticodingseasons.py b/experiments/karines_experiments/hyperplasticodingseasons.py
new file mode 100644
index 0000000000..1f6b0e68df
--- /dev/null
+++ b/experiments/karines_experiments/hyperplasticodingseasons.py
@@ -0,0 +1,177 @@
+#!/usr/bin/env python3
+import asyncio
+
+from pyrevolve import parser
+from pyrevolve.evolution import fitness
+from pyrevolve.evolution.selection import multiple_selection, tournament_selection
+from pyrevolve.evolution.population import Population, PopulationConfig
+from pyrevolve.evolution.pop_management.steady_state import steady_state_population_management
+from pyrevolve.experiment_management import ExperimentManagement
+from pyrevolve.genotype.hyperplasticoding_v2.crossover.crossover import CrossoverConfig
+from pyrevolve.genotype.hyperplasticoding_v2.crossover.standard_crossover import standard_crossover
+from pyrevolve.genotype.hyperplasticoding_v2.initialization import random_initialization
+from pyrevolve.genotype.hyperplasticoding_v2.mutation.mutation import MutationConfig
+from pyrevolve.genotype.hyperplasticoding_v2.mutation.standard_mutation import standard_mutation
+from pyrevolve.genotype.hyperplasticoding_v2.hyperplasticoding import HyperPlasticodingConfig
+from pyrevolve.tol.manage import measures
+from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue
+from pyrevolve.util.supervisor.analyzer_queue import AnalyzerQueue
+from pyrevolve.custom_logging.logger import logger
+import sys
+
+
+async def run():
+ """
+ The main coroutine, which is started below.
+ """
+
+ # experiment params #
+ num_generations = 200
+ population_size = 100
+ offspring_size = 100
+ front = 'slaves'
+
+ # environment world and z-start
+ environments = {'plane': 0.03,
+ 'tilted3': 0.08 }
+
+ # calculation of the measures can be on or off, because they are expensive
+ novelty_on = {'novelty': False,
+ 'novelty_pop': True,
+ 'measures': ['branching',
+ 'limbs',
+ 'length_of_limbs',
+ 'coverage',
+ 'joints',
+ 'proportion',
+ 'size',
+ 'symmetry']
+ }
+
+ cppn_config_path = 'pyrevolve/genotype/hyperplasticoding_v2/config-plastic'
+
+ genotype_conf = HyperPlasticodingConfig(
+ plastic=True,
+ cppn_config_path=cppn_config_path
+ )
+
+ mutation_conf = MutationConfig(
+ mutation_prob=1,
+ genotype_conf=genotype_conf,
+ cppn_config_path=cppn_config_path
+ )
+
+ crossover_conf = CrossoverConfig(
+ crossover_prob=0,
+ cppn_config_path=cppn_config_path
+ )
+
+ # experiment params #
+
+ # Parse command line / file input arguments
+ settings = parser.parse_args()
+
+ experiment_management = ExperimentManagement(settings, environments)
+ do_recovery = settings.recovery_enabled and not experiment_management.experiment_is_new()
+
+
+ logger.info('Activated run '+settings.run+' of experiment '+settings.experiment_name)
+
+ if do_recovery:
+ gen_num, has_offspring, next_robot_id = experiment_management.read_recovery_state(population_size,
+ offspring_size)
+ if gen_num == num_generations-1:
+ logger.info('Experiment is already complete.')
+ return
+ else:
+ gen_num = 0
+ next_robot_id = 1
+
+ def fitness_function_plane(measures, robot):
+ return fitness.displacement_velocity_hill(measures, robot)
+
+ # using the same function
+ fitness_function = {'plane': fitness_function_plane,
+ 'tilted3': fitness_function_plane}
+
+ population_conf = PopulationConfig(
+ population_size=population_size,
+ genotype_constructor=random_initialization,
+ genotype_conf=genotype_conf,
+ fitness_function=fitness_function,
+ mutation_operator=standard_mutation,
+ mutation_conf=mutation_conf,
+ crossover_operator=standard_crossover,
+ crossover_conf=crossover_conf,
+ selection=lambda individuals: tournament_selection(individuals, environments, 2),
+ parent_selection=lambda individuals: multiple_selection(individuals, 2, tournament_selection, environments),
+ population_management=steady_state_population_management,
+ population_management_selector=tournament_selection,
+ evaluation_time=settings.evaluation_time,
+ offspring_size=offspring_size,
+ experiment_name=settings.experiment_name,
+ experiment_management=experiment_management,
+ environments=environments,
+ novelty_on=novelty_on,
+ front=front,
+ run_simulation=settings.run_simulation,
+ all_settings=settings,
+ )
+
+ simulator_queue = {}
+ analyzer_queue = None
+
+ if settings.run_simulation == 1:
+ previous_port = None
+ for environment in environments:
+
+ settings.world = environment
+ settings.z_start = environments[environment]
+
+ if previous_port is None:
+ port = settings.port_start
+ previous_port = port
+ else:
+ port = previous_port+settings.n_cores
+ previous_port = port
+
+ simulator_queue[environment] = SimulatorQueue(settings.n_cores, settings, port)
+ await simulator_queue[environment].start()
+
+ analyzer_queue = AnalyzerQueue(1, settings, port+settings.n_cores)
+ await analyzer_queue.start()
+
+ population = Population(population_conf, simulator_queue, analyzer_queue, next_robot_id)
+
+ if do_recovery:
+
+ population.load_novelty_archive()
+
+ if gen_num >= 0:
+ # loading a previous state of the experiment
+ await population.load_snapshot(gen_num)
+ logger.info('Recovered snapshot '+str(gen_num)+', pop with ' + str(len(population.individuals))+' individuals')
+
+ if has_offspring:
+ individuals = await population.load_offspring(gen_num, population_size, offspring_size, next_robot_id)
+ gen_num += 1
+ logger.info('Recovered unfinished offspring '+str(gen_num))
+
+ if gen_num == 0:
+ await population.init_pop(individuals)
+ else:
+ population = await population.next_gen(gen_num, individuals)
+
+ experiment_management.export_snapshots(population.individuals, gen_num)
+ else:
+ # starting a new experiment
+ experiment_management.create_exp_folders()
+ await population.init_pop()
+ experiment_management.export_snapshots(population.individuals, gen_num)
+
+ while gen_num < num_generations-1:
+ gen_num += 1
+ population = await population.next_gen(gen_num)
+ experiment_management.export_snapshots(population.individuals, gen_num)
+
+ # output result after completing all generations...
\ No newline at end of file
diff --git a/experiments/karines_experiments/hyperplasticodingseasonsI15.py b/experiments/karines_experiments/hyperplasticodingseasonsI15.py
new file mode 100644
index 0000000000..1f6b0e68df
--- /dev/null
+++ b/experiments/karines_experiments/hyperplasticodingseasonsI15.py
@@ -0,0 +1,177 @@
+#!/usr/bin/env python3
+import asyncio
+
+from pyrevolve import parser
+from pyrevolve.evolution import fitness
+from pyrevolve.evolution.selection import multiple_selection, tournament_selection
+from pyrevolve.evolution.population import Population, PopulationConfig
+from pyrevolve.evolution.pop_management.steady_state import steady_state_population_management
+from pyrevolve.experiment_management import ExperimentManagement
+from pyrevolve.genotype.hyperplasticoding_v2.crossover.crossover import CrossoverConfig
+from pyrevolve.genotype.hyperplasticoding_v2.crossover.standard_crossover import standard_crossover
+from pyrevolve.genotype.hyperplasticoding_v2.initialization import random_initialization
+from pyrevolve.genotype.hyperplasticoding_v2.mutation.mutation import MutationConfig
+from pyrevolve.genotype.hyperplasticoding_v2.mutation.standard_mutation import standard_mutation
+from pyrevolve.genotype.hyperplasticoding_v2.hyperplasticoding import HyperPlasticodingConfig
+from pyrevolve.tol.manage import measures
+from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue
+from pyrevolve.util.supervisor.analyzer_queue import AnalyzerQueue
+from pyrevolve.custom_logging.logger import logger
+import sys
+
+
+async def run():
+ """
+ The main coroutine, which is started below.
+ """
+
+ # experiment params #
+ num_generations = 200
+ population_size = 100
+ offspring_size = 100
+ front = 'slaves'
+
+ # environment world and z-start
+ environments = {'plane': 0.03,
+ 'tilted3': 0.08 }
+
+ # calculation of the measures can be on or off, because they are expensive
+ novelty_on = {'novelty': False,
+ 'novelty_pop': True,
+ 'measures': ['branching',
+ 'limbs',
+ 'length_of_limbs',
+ 'coverage',
+ 'joints',
+ 'proportion',
+ 'size',
+ 'symmetry']
+ }
+
+ cppn_config_path = 'pyrevolve/genotype/hyperplasticoding_v2/config-plastic'
+
+ genotype_conf = HyperPlasticodingConfig(
+ plastic=True,
+ cppn_config_path=cppn_config_path
+ )
+
+ mutation_conf = MutationConfig(
+ mutation_prob=1,
+ genotype_conf=genotype_conf,
+ cppn_config_path=cppn_config_path
+ )
+
+ crossover_conf = CrossoverConfig(
+ crossover_prob=0,
+ cppn_config_path=cppn_config_path
+ )
+
+ # experiment params #
+
+ # Parse command line / file input arguments
+ settings = parser.parse_args()
+
+ experiment_management = ExperimentManagement(settings, environments)
+ do_recovery = settings.recovery_enabled and not experiment_management.experiment_is_new()
+
+
+ logger.info('Activated run '+settings.run+' of experiment '+settings.experiment_name)
+
+ if do_recovery:
+ gen_num, has_offspring, next_robot_id = experiment_management.read_recovery_state(population_size,
+ offspring_size)
+ if gen_num == num_generations-1:
+ logger.info('Experiment is already complete.')
+ return
+ else:
+ gen_num = 0
+ next_robot_id = 1
+
+ def fitness_function_plane(measures, robot):
+ return fitness.displacement_velocity_hill(measures, robot)
+
+ # using the same function
+ fitness_function = {'plane': fitness_function_plane,
+ 'tilted3': fitness_function_plane}
+
+ population_conf = PopulationConfig(
+ population_size=population_size,
+ genotype_constructor=random_initialization,
+ genotype_conf=genotype_conf,
+ fitness_function=fitness_function,
+ mutation_operator=standard_mutation,
+ mutation_conf=mutation_conf,
+ crossover_operator=standard_crossover,
+ crossover_conf=crossover_conf,
+ selection=lambda individuals: tournament_selection(individuals, environments, 2),
+ parent_selection=lambda individuals: multiple_selection(individuals, 2, tournament_selection, environments),
+ population_management=steady_state_population_management,
+ population_management_selector=tournament_selection,
+ evaluation_time=settings.evaluation_time,
+ offspring_size=offspring_size,
+ experiment_name=settings.experiment_name,
+ experiment_management=experiment_management,
+ environments=environments,
+ novelty_on=novelty_on,
+ front=front,
+ run_simulation=settings.run_simulation,
+ all_settings=settings,
+ )
+
+ simulator_queue = {}
+ analyzer_queue = None
+
+ if settings.run_simulation == 1:
+ previous_port = None
+ for environment in environments:
+
+ settings.world = environment
+ settings.z_start = environments[environment]
+
+ if previous_port is None:
+ port = settings.port_start
+ previous_port = port
+ else:
+ port = previous_port+settings.n_cores
+ previous_port = port
+
+ simulator_queue[environment] = SimulatorQueue(settings.n_cores, settings, port)
+ await simulator_queue[environment].start()
+
+ analyzer_queue = AnalyzerQueue(1, settings, port+settings.n_cores)
+ await analyzer_queue.start()
+
+ population = Population(population_conf, simulator_queue, analyzer_queue, next_robot_id)
+
+ if do_recovery:
+
+ population.load_novelty_archive()
+
+ if gen_num >= 0:
+ # loading a previous state of the experiment
+ await population.load_snapshot(gen_num)
+ logger.info('Recovered snapshot '+str(gen_num)+', pop with ' + str(len(population.individuals))+' individuals')
+
+ if has_offspring:
+ individuals = await population.load_offspring(gen_num, population_size, offspring_size, next_robot_id)
+ gen_num += 1
+ logger.info('Recovered unfinished offspring '+str(gen_num))
+
+ if gen_num == 0:
+ await population.init_pop(individuals)
+ else:
+ population = await population.next_gen(gen_num, individuals)
+
+ experiment_management.export_snapshots(population.individuals, gen_num)
+ else:
+ # starting a new experiment
+ experiment_management.create_exp_folders()
+ await population.init_pop()
+ experiment_management.export_snapshots(population.individuals, gen_num)
+
+ while gen_num < num_generations-1:
+ gen_num += 1
+ population = await population.next_gen(gen_num)
+ experiment_management.export_snapshots(population.individuals, gen_num)
+
+ # output result after completing all generations...
\ No newline at end of file
diff --git a/experiments/karines_experiments/hyperplasticodingt3.py b/experiments/karines_experiments/hyperplasticodingt3.py
new file mode 100644
index 0000000000..5c8c22095f
--- /dev/null
+++ b/experiments/karines_experiments/hyperplasticodingt3.py
@@ -0,0 +1,174 @@
+#!/usr/bin/env python3
+import asyncio
+
+from pyrevolve import parser
+from pyrevolve.evolution import fitness
+from pyrevolve.evolution.selection import multiple_selection, tournament_selection
+from pyrevolve.evolution.population import Population, PopulationConfig
+from pyrevolve.evolution.pop_management.steady_state import steady_state_population_management
+from pyrevolve.experiment_management import ExperimentManagement
+from pyrevolve.genotype.hyperplasticoding_v2.crossover.crossover import CrossoverConfig
+from pyrevolve.genotype.hyperplasticoding_v2.crossover.standard_crossover import standard_crossover
+from pyrevolve.genotype.hyperplasticoding_v2.initialization import random_initialization
+from pyrevolve.genotype.hyperplasticoding_v2.mutation.mutation import MutationConfig
+from pyrevolve.genotype.hyperplasticoding_v2.mutation.standard_mutation import standard_mutation
+from pyrevolve.genotype.hyperplasticoding_v2.hyperplasticoding import HyperPlasticodingConfig
+from pyrevolve.tol.manage import measures
+from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue
+from pyrevolve.util.supervisor.analyzer_queue import AnalyzerQueue
+from pyrevolve.custom_logging.logger import logger
+import sys
+
+
+async def run():
+ """
+ The main coroutine, which is started below.
+ """
+
+ # experiment params #
+ num_generations = 200
+ population_size = 100
+ offspring_size = 100
+ front = 'none'
+
+ # environment world and z-start
+ environments = { 'tilted3': 0.08 }
+
+ # calculation of the measures can be on or off, because they are expensive
+ novelty_on = {'novelty': False,
+ 'novelty_pop': True,
+ 'measures': ['branching',
+ 'limbs',
+ 'length_of_limbs',
+ 'coverage',
+ 'joints',
+ 'proportion',
+ 'size',
+ 'symmetry']
+ }
+
+ cppn_config_path = 'pyrevolve/genotype/hyperplasticoding_v2/config-nonplastic'
+
+ genotype_conf = HyperPlasticodingConfig(
+ plastic=False,
+ cppn_config_path=cppn_config_path
+ )
+
+ mutation_conf = MutationConfig(
+ mutation_prob=1,
+ genotype_conf=genotype_conf,
+ cppn_config_path=cppn_config_path
+ )
+
+ crossover_conf = CrossoverConfig(
+ crossover_prob=0,
+ cppn_config_path=cppn_config_path
+ )
+
+ # experiment params #
+
+ # Parse command line / file input arguments
+ settings = parser.parse_args()
+
+ experiment_management = ExperimentManagement(settings, environments)
+ do_recovery = settings.recovery_enabled and not experiment_management.experiment_is_new()
+
+
+ logger.info('Activated run '+settings.run+' of experiment '+settings.experiment_name)
+
+ if do_recovery:
+ gen_num, has_offspring, next_robot_id = experiment_management.read_recovery_state(population_size,
+ offspring_size)
+ if gen_num == num_generations-1:
+ logger.info('Experiment is already complete.')
+ return
+ else:
+ gen_num = 0
+ next_robot_id = 1
+
+ def fitness_function_plane(measures, robot):
+ return fitness.displacement_velocity_hill(measures, robot)
+
+ fitness_function = {'tilted3': fitness_function_plane}
+
+ population_conf = PopulationConfig(
+ population_size=population_size,
+ genotype_constructor=random_initialization,
+ genotype_conf=genotype_conf,
+ fitness_function=fitness_function,
+ mutation_operator=standard_mutation,
+ mutation_conf=mutation_conf,
+ crossover_operator=standard_crossover,
+ crossover_conf=crossover_conf,
+ selection=lambda individuals: tournament_selection(individuals, environments, 2),
+ parent_selection=lambda individuals: multiple_selection(individuals, 2, tournament_selection, environments),
+ population_management=steady_state_population_management,
+ population_management_selector=tournament_selection,
+ evaluation_time=settings.evaluation_time,
+ offspring_size=offspring_size,
+ experiment_name=settings.experiment_name,
+ experiment_management=experiment_management,
+ environments=environments,
+ novelty_on=novelty_on,
+ front=front,
+ run_simulation=settings.run_simulation,
+ all_settings=settings,
+ )
+
+ simulator_queue = {}
+ analyzer_queue = None
+
+ if settings.run_simulation == 1:
+ previous_port = None
+ for environment in environments:
+
+ settings.world = environment
+ settings.z_start = environments[environment]
+
+ if previous_port is None:
+ port = settings.port_start
+ previous_port = port
+ else:
+ port = previous_port+settings.n_cores
+ previous_port = port
+
+ simulator_queue[environment] = SimulatorQueue(settings.n_cores, settings, port)
+ await simulator_queue[environment].start()
+
+ analyzer_queue = AnalyzerQueue(1, settings, port+settings.n_cores)
+ await analyzer_queue.start()
+
+ population = Population(population_conf, simulator_queue, analyzer_queue, next_robot_id)
+
+ if do_recovery:
+
+ population.load_novelty_archive()
+
+ if gen_num >= 0:
+ # loading a previous state of the experiment
+ await population.load_snapshot(gen_num)
+ logger.info('Recovered snapshot '+str(gen_num)+', pop with ' + str(len(population.individuals))+' individuals')
+
+ if has_offspring:
+ individuals = await population.load_offspring(gen_num, population_size, offspring_size, next_robot_id)
+ gen_num += 1
+ logger.info('Recovered unfinished offspring '+str(gen_num))
+
+ if gen_num == 0:
+ await population.init_pop(individuals)
+ else:
+ population = await population.next_gen(gen_num, individuals)
+
+ experiment_management.export_snapshots(population.individuals, gen_num)
+ else:
+ # starting a new experiment
+ experiment_management.create_exp_folders()
+ await population.init_pop()
+ experiment_management.export_snapshots(population.individuals, gen_num)
+
+ while gen_num < num_generations-1:
+ gen_num += 1
+ population = await population.next_gen(gen_num)
+ experiment_management.export_snapshots(population.individuals, gen_num)
+
+ # output result after completing all generations...
\ No newline at end of file
diff --git a/experiments/karines_experiments/plots_intermethods.r b/experiments/karines_experiments/plots_intermethods.r
index 799aa90400..59fe690ca9 100644
--- a/experiments/karines_experiments/plots_intermethods.r
+++ b/experiments/karines_experiments/plots_intermethods.r
@@ -13,43 +13,37 @@ library(viridis)
#### CHANGE THE PARAMETERS HERE ####
-base_directory <- c('data/hyper_big',
- 'data', 'data', 'data', 'data')
+base_directory <- c(
+ '/storage/karine/hyper_big', 'data', '/storage/karine/hyper_big')
-analysis = 'analysis_t3'
+analysis = 'analysis'
output_directory = paste(base_directory[2],'/',analysis ,sep='')
experiments_type = c('hyperplasticoding_p',
- 'hyperplasticodingt3',
- 'hyperplasticodingt4',
- 'hyperplasticodingoldt3',
- 'hyperplasticodingoldt4' )
-runs = list(c(1:10),
- c(1:10) ,
- c(1:10),
- c(1:10),
- c(1:10))
+
+ 'hyperplasticodingseasons', 'hyperplasticodingt3' )
+runs = list(c(1:5),
+ c(1:5) ,
+ c(1:5))
environments = list( c('plane'),
- c('tilted3') ,
- c('tilted4'),
- c('tilted3') ,
- c('tilted4')
+
+ c('plane', 'tilted3'),
+ c('tilted3')
)
# methods are product of experiments_type VS environments and should be coupled with colors.
# make sure to define methods_labels in alphabetic order, and experiments_type accordingly
-methods_labels = c( 'hyperplasticoding_p',
- 'hyperplasticodingt3',
- 'hyperplasticodingt4',
- 'hyperplasticodingoldt3',
- 'hyperplasticodingoldt4') # note that labels of Plane death and Tilted death are INVERTED on purpose, to fix the mistake done when naming the experiments.
+methods_labels = c( 'plane',
+ 'plastic plane',
+ 'plastic tilted',
+ 'tilted'
+ ) # note that labels of Plane death and Tilted death are INVERTED on purpose, to fix the mistake done when naming the experiments.
experiments_type_colors = c('#009900',
'#EE8610',
'#7550ff',
- '#EE8245',
- '#8760ff')
+ '#876044' )
#aggregations = c('min', 'Q25','mean', 'median', 'Q75','max')
aggregations = c('median')
@@ -328,7 +322,7 @@ for (i in 1:length(measures_names))
graph = graph + labs(y=measures_labels[i], x="Generation", title="")
graph = graph + scale_color_manual(values=experiments_type_colors)
- graph = graph + theme(legend.position="bottom" , legend.text=element_text(size=25), axis.text=element_text(size=32), axis.title=element_text(size=30),
+ graph = graph + theme(legend.position="right" , legend.text=element_text(size=25), axis.text=element_text(size=32), axis.title=element_text(size=30),
plot.subtitle=element_text(size=30 ), plot.title=element_text(size=30 ))
ggsave(paste( output_directory,'/',measures_names[i], '_', aggregations[a], '_lines.pdf', sep=''), graph , device='pdf', height = 10, width = 10)
@@ -396,7 +390,8 @@ for (i in 1:length(measures_names))
g1 = g1 + geom_signif( test="wilcox.test", size=1, textsize=14, step_increase=0.15,
comparisons = comps,
- map_signif_level=c("***"=0.001,"**"=0.01, "*"=0.05) )
+ #map_signif_level=c("***"=0.001,"**"=0.01, "*"=0.05) )
+ map_signif_level=c( ) )
if (out == 'full' || (out == 'filtered' && has_outliers == TRUE) ){
ggsave(paste(output_directory,"/",measures_names[i],"_",gc,"_", aggregations[a],'_', out,"_boxes.pdf",sep = ""), g1, device = "pdf", height=18, width = 10)
diff --git a/experiments/karines_experiments/render_bestrobots.r b/experiments/karines_experiments/render_bestrobots.r
index 11a6ba80fb..30fd21cd8a 100644
--- a/experiments/karines_experiments/render_bestrobots.r
+++ b/experiments/karines_experiments/render_bestrobots.r
@@ -5,27 +5,22 @@ require('magick')
##### change paths/labels/params here #####
-paths = c('hyperplasticodingt4',
- 'hyperplasticodingoldt4',
- 'hyperplasticodingoldt3')
+paths = c('hyperplasticodingseasons' )
environments = list(
- c( 'tilted4'),
- c( 'tilted4'),
- c( 'tilted3')#,
- #c( 'tilted5')
+ c('plane', 'tilted3')
+
)
-colors = list( c('#ffffff'),c('#ffffff'),
- c('#ffffff') )
+colors = list( c('#ffffff','#ffff44') )
base_directory <- paste('data/', sep='')
-analysis = 'analysis_t3'
+analysis = 'analysis'
-runs = list( c(1:10),c(1:10),c(1:10))
+runs = list( c(1:5),c(1:10),c(1:10))
pop = 100
-num_top = 3
+num_top = 20
gens = c(149)
criteria = c('desc')
diff --git a/experiments/karines_experiments/setup-experiments.sh b/experiments/karines_experiments/setup-experiments.sh
index 38fa2d29c6..1b4a8d4d69 100755
--- a/experiments/karines_experiments/setup-experiments.sh
+++ b/experiments/karines_experiments/setup-experiments.sh
@@ -2,12 +2,12 @@
#set -e
#set -x
-runs=10
+runs=5
-num_terminals=5
+num_terminals=6
start_port=8000
-final_gen=149
-experiments=("hyperplasticodingseasons")
+final_gen=199
+experiments=("hyperplasticodingseasonsI15" "hyperplasticodingp" "hyperplasticodingt3")
experiments_path=karines_experiments/data/
managers_path=experiments/karines_experiments/
diff --git a/models/tilted3/meshes/tilted3.dae b/models/tilted3/meshes/tilted3.dae
new file mode 100644
index 0000000000..da8af6c855
--- /dev/null
+++ b/models/tilted3/meshes/tilted3.dae
@@ -0,0 +1,89 @@
+
+
+
+
+ Blender User
+ Blender 2.92.0 commit date:2021-02-24, commit time:16:25, hash:02948a2cab44
+
+ 2021-03-15T16:01:27
+ 2021-03-15T16:01:27
+
+ Z_UP
+
+
+
+
+
+
+
+ 0 0 0 1
+
+
+ 0.01834756 0.3800506 0.06089931 1
+
+
+ 1.45
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 0 2 0 0 0 1 0 3 0 2 0
+
+
+
+
+
+
+
+ 11.96257 0 0 -0.3712567 0 8.05979 -0.05233596 0 0 0.4223957 0.9986295 0 0 0 0 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/models/tilted3/model.config b/models/tilted3/model.config
new file mode 100644
index 0000000000..9c8d506a9c
--- /dev/null
+++ b/models/tilted3/model.config
@@ -0,0 +1,16 @@
+
+
+
+ Ground Plane
+ 1.0
+ model.sdf
+
+
+ Nate Koenig
+ nate@osrfoundation.org
+
+
+
+ A simple ground plane.
+
+
diff --git a/models/tilted4/meshes/tilted4.dae b/models/tilted4/meshes/tilted4.dae
new file mode 100644
index 0000000000..ec80dbc124
--- /dev/null
+++ b/models/tilted4/meshes/tilted4.dae
@@ -0,0 +1,89 @@
+
+
+
+
+ Blender User
+ Blender 2.92.0 commit date:2021-02-24, commit time:16:25, hash:02948a2cab44
+
+ 2021-03-16T23:46:43
+ 2021-03-16T23:46:43
+
+ Z_UP
+
+
+
+
+
+
+
+ 0 0 0 1
+
+
+ 0.01834756 0.3800506 0.06089931 1
+
+
+ 1.45
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 0 2 0 0 0 1 0 3 0 2 0
+
+
+
+
+
+
+
+ 11.96257 0 0 -0.3712567 0 8.05119 -0.06975647 0 0 0.5629941 0.9975641 0 0 0 0 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/models/tilted4/model.config b/models/tilted4/model.config
new file mode 100644
index 0000000000..9c8d506a9c
--- /dev/null
+++ b/models/tilted4/model.config
@@ -0,0 +1,16 @@
+
+
+
+ Ground Plane
+ 1.0
+ model.sdf
+
+
+ Nate Koenig
+ nate@osrfoundation.org
+
+
+
+ A simple ground plane.
+
+
diff --git a/pyrevolve/evolution/__pycache__/selection.cpython-37.pyc b/pyrevolve/evolution/__pycache__/selection.cpython-37.pyc
index 72f6c84aae..169337771e 100644
Binary files a/pyrevolve/evolution/__pycache__/selection.cpython-37.pyc and b/pyrevolve/evolution/__pycache__/selection.cpython-37.pyc differ
diff --git a/pyrevolve/genotype/hyperplasticoding_v2/config-plastic b/pyrevolve/genotype/hyperplasticoding_v2/config-plastic
new file mode 100644
index 0000000000..d62eb469b7
--- /dev/null
+++ b/pyrevolve/genotype/hyperplasticoding_v2/config-plastic
@@ -0,0 +1,85 @@
+[NEAT]
+fitness_criterion = max
+fitness_threshold = 100
+pop_size = 150
+reset_on_extinction = False
+
+[DefaultGenome]
+# node activation options
+activation_default = random
+activation_mutate_rate = 0.1
+activation_options = sigmoid sin gauss tanh abs inv
+
+# network parameters.
+# inputs: x dest, y dest, inclination
+# outputs: b_module, b2_module, a1_module, a2_module, period, phase_offset, amplitude
+num_hidden = 0
+#num_hidden = 2
+num_inputs = 3
+num_outputs = 7
+
+# connection add/remove rates
+conn_add_prob = 0.2
+conn_delete_prob = 0.2
+
+# node add/remove rates
+node_add_prob = 0.1
+node_delete_prob = 0.1
+
+# node aggregation options
+aggregation_default = sum
+aggregation_mutate_rate = 0.0
+aggregation_options = sum
+
+# node bias options
+bias_init_mean = 0
+bias_init_stdev = 0
+bias_max_value = 30
+bias_min_value = -30
+bias_mutate_power = 0.5
+bias_mutate_rate = 0.7
+bias_replace_rate = 0.1
+
+# genome compatibility options
+compatibility_disjoint_coefficient = 1.0
+compatibility_weight_coefficient = 0.5
+
+# connection enable options
+enabled_default = True
+enabled_mutate_rate = 0.01
+
+feed_forward = True
+initial_connection = full
+#initial_connection = full_direct
+
+# node response options
+response_init_mean = 1.0
+response_init_stdev = 0.0
+response_max_value = 30.0
+response_min_value = -30.0
+response_mutate_power = 0.0
+response_mutate_rate = 0.0
+response_replace_rate = 0.0
+
+# connection weight options
+#weight_init_type = uniform
+weight_init_mean = 0.0
+weight_init_stdev = 1
+weight_max_value = 30
+weight_min_value = -30
+weight_mutate_power = 0.5
+weight_mutate_rate = 0.8
+weight_replace_rate = 0.1
+
+[DefaultSpeciesSet]
+compatibility_threshold = 3
+
+[DefaultStagnation]
+species_fitness_func = max
+max_stagnation = 20
+species_elitism = 2
+
+[DefaultReproduction]
+elitism = 2
+survival_threshold = 0.2
+
diff --git a/pyrevolve/genotype/hyperplasticoding_v2/hyperplasticoding.py b/pyrevolve/genotype/hyperplasticoding_v2/hyperplasticoding.py
index b03c5adfbc..b443540f26 100644
--- a/pyrevolve/genotype/hyperplasticoding_v2/hyperplasticoding.py
+++ b/pyrevolve/genotype/hyperplasticoding_v2/hyperplasticoding.py
@@ -68,7 +68,6 @@ def random_init(self):
def develop(self, environment):
- print('\n', environment)
# Applyies regulation according to environmental conditions.
if self.conf.plastic:
@@ -77,7 +76,7 @@ def develop(self, environment):
if environment == 'plane':
self.environmental_conditions['inclined'] = 0
if environment == 'tilted3':
- self.environmental_conditions['inclined'] = 1
+ self.environmental_conditions['inclined'] = 15
self.random = random.Random(self.querying_seed)
@@ -294,7 +293,11 @@ def get_angle(self, module_type, parent):
def query_body_part(self, x_dest, y_dest, cppn):
- outputs = cppn.activate(( self.environmental_conditions['inclined'], x_dest, y_dest))
+ if self.conf.plastic:
+ outputs = cppn.activate(( self.environmental_conditions['inclined'], x_dest, y_dest))
+ else:
+ outputs = cppn.activate(( x_dest, y_dest))
+
which_module = {
'b_module': outputs[0],
@@ -309,7 +312,11 @@ def query_body_part(self, x_dest, y_dest, cppn):
def query_brain_part(self, x_dest, y_dest, cppn):
- outputs = cppn.activate(( self.environmental_conditions['inclined'], x_dest, y_dest))
+ if self.conf.plastic:
+ outputs = cppn.activate(( self.environmental_conditions['inclined'], x_dest, y_dest))
+ else:
+ outputs = cppn.activate(( x_dest, y_dest))
+
params = {
'period': outputs[4],
'phase_offset': outputs[5],
diff --git a/worlds/plane.world.record b/worlds/plane.world.record
new file mode 100644
index 0000000000..02edbb6610
--- /dev/null
+++ b/worlds/plane.world.record
@@ -0,0 +1,69 @@
+
+
+
+
+ 0
+ 0
+
+
+ 0.005
+
+ 200
+
+
+
+
+ 0.1
+ 10e-6
+
+ 100
+ 1e-8
+
+
+ world
+
+
+
+
+
+
+ model://sun
+
+
+ model://tol_ground
+
+
+
+ true
+ -3 3 2 0 0.3 -1.1
+
+
+
+
+ 0.1 0.1 0.1
+
+
+
+
+
+
+ /net/ripper2/home/karinemiras/projects/revolve/experiments/karines_experiments
+
+ 1.047
+
+ 1920
+ 1080
+
+
+ 0.1
+ 100
+
+
+ 1
+ 4
+
+
+
+
+
\ No newline at end of file
diff --git a/worlds/tilted3.world b/worlds/tilted3.world
new file mode 100644
index 0000000000..467b1bf78d
--- /dev/null
+++ b/worlds/tilted3.world
@@ -0,0 +1,40 @@
+
+
+
+
+ 0
+ 0
+
+
+ 0.003
+
+
+ 0
+
+
+
+ 0.1
+ 10e-6
+
+
+ 100
+ 1e-8
+
+
+ quick
+
+
+
+
+
+
+
+ model://sun
+
+
+ model://tilted3
+
+
+
+
+
diff --git a/worlds/tilted4.world b/worlds/tilted4.world
new file mode 100644
index 0000000000..900a9ae62c
--- /dev/null
+++ b/worlds/tilted4.world
@@ -0,0 +1,40 @@
+
+
+
+
+ 0
+ 0
+
+
+ 0.003
+
+
+ 0
+
+
+
+ 0.1
+ 10e-6
+
+
+ 100
+ 1e-8
+
+
+ quick
+
+
+
+
+
+
+
+ model://sun
+
+
+ model://tilted4
+
+
+
+
+