diff --git a/rl_studio/README.md b/rl_studio/README.md new file mode 100644 index 000000000..29a640cab --- /dev/null +++ b/rl_studio/README.md @@ -0,0 +1,15 @@ +# Run RL Studio + +## Usage + +You can run a simple RLStudio trainer typing: + +```bash +python main_rlstudio.py -n qlearn -a f1 -e simple -f config.yaml +``` + +Open the `config.yaml` file and set the params you need. + +## Project diagram + +![](./docs/rlstudio-diagram.png) diff --git a/rl_studio/agents/__init__.py b/rl_studio/agents/__init__.py index e69de29bb..179c12c86 100644 --- a/rl_studio/agents/__init__.py +++ b/rl_studio/agents/__init__.py @@ -0,0 +1,20 @@ +from rl_studio.agents.agents_type import AgentsType +from rl_studio.agents.exceptions import NoValidTrainingType + + +class TrainerFactory: + def __new__(cls, config): + + agent = config.agent["name"] + + if agent == AgentsType.F1.value: + from rl_studio.agents.f1.train_qlearn import F1Trainer + return F1Trainer(config) + + elif agent == AgentsType.TURTLEBOT.value: + from rl_studio.agents.turtlebot.turtlebot_trainer import TurtlebotTrainer + + return TurtlebotTrainer(config) + + else: + raise NoValidTrainingType(agent) diff --git a/rl_studio/agents/agents_type.py b/rl_studio/agents/agents_type.py new file mode 100644 index 000000000..b9b757909 --- /dev/null +++ b/rl_studio/agents/agents_type.py @@ -0,0 +1,6 @@ +from enum import Enum + + +class AgentsType(Enum): + F1 = "f1" + TURTLEBOT = "turtlebot" diff --git a/rl_studio/agents/exceptions.py b/rl_studio/agents/exceptions.py new file mode 100644 index 000000000..471e37aed --- /dev/null +++ b/rl_studio/agents/exceptions.py @@ -0,0 +1,9 @@ +class CreationError(Exception): + ... + + +class NoValidTrainingType(CreationError): + def __init__(self, training_type): + self.traning_type = training_type + self.message = f"[ERROR] No valid training type ({training_type}) in your config.yml file or is missing." + super().__init__(self.message) diff --git a/rl_studio/agents/f1/__init__.py b/rl_studio/agents/f1/__init__.py index e1ad4b09a..e69de29bb 100644 --- a/rl_studio/agents/f1/__init__.py +++ b/rl_studio/agents/f1/__init__.py @@ -1 +0,0 @@ -from rl_studio.envs.gazebo_env import * diff --git a/rl_studio/agents/f1/brains/train_qlearn.py b/rl_studio/agents/f1/brains/train_qlearn.py deleted file mode 100755 index 0f9485e9f..000000000 --- a/rl_studio/agents/f1/brains/train_qlearn.py +++ /dev/null @@ -1,216 +0,0 @@ -import datetime -import time -from functools import reduce - -import gym -import numpy as np - -from rl_studio.agents.f1 import liveplot -from rl_studio.agents.f1.settings import QLearnConfig -from rl_studio.agents.f1 import utils -from algorithms.qlearn import QLearn -from rl_studio.visual.ascii.images import JDEROBOT_LOGO -from rl_studio.visual.ascii.text import JDEROBOT, QLEARN_CAMERA, LETS_GO - - -def main(): - - print(JDEROBOT) - print(JDEROBOT_LOGO) - print(QLEARN_CAMERA) - print(f"\t- Start hour: {datetime.datetime.now()}") - - config = QLearnConfig() - - environment = config.envs_params["simple"] - env = gym.make(environment["env"], **environment) - - # TODO: Move to settings file - outdir = "./logs/f1_qlearn_gym_experiments/" - stats = {} # epoch: steps - states_counter = {} - states_reward = {} - - plotter = liveplot.LivePlot(outdir) - - last_time_steps = np.ndarray(0) - - actions = range(env.action_space.n) - env = gym.wrappers.Monitor(env, outdir, force=True) - counter = 0 - estimate_step_per_lap = environment["estimated_steps"] - lap_completed = False - total_episodes = 20000 - epsilon_discount = 0.9986 # Default 0.9986 - - qlearn = QLearn(actions=actions, alpha=0.8, gamma=0.9, epsilon=0.99) - - if config.load_model: - # TODO: Folder to models. Maybe from environment variable? - file_name = "" - utils.load_model(qlearn, file_name) - highest_reward = max(qlearn.q.values(), key=stats.get) - else: - highest_reward = 0 - initial_epsilon = qlearn.epsilon - - telemetry_start_time = time.time() - start_time = datetime.datetime.now() - start_time_format = start_time.strftime("%Y%m%d_%H%M") - - print(LETS_GO) - - previous = datetime.datetime.now() - checkpoints = [] # "ID" - x, y - time - - # START - for episode in range(total_episodes): - - counter = 0 - done = False - lap_completed = False - - cumulated_reward = 0 - observation = env.reset() - - if qlearn.epsilon > 0.05: - qlearn.epsilon *= epsilon_discount - - state = "".join(map(str, observation)) - - for step in range(500000): - - counter += 1 - - # Pick an action based on the current state - action = qlearn.selectAction(state) - - # Execute the action and get feedback - observation, reward, done, info = env.step(action) - cumulated_reward += reward - - if highest_reward < cumulated_reward: - highest_reward = cumulated_reward - - nextState = "".join(map(str, observation)) - - try: - states_counter[nextState] += 1 - except KeyError: - states_counter[nextState] = 1 - - qlearn.learn(state, action, reward, nextState) - - env._flush(force=True) - - if config.save_positions: - now = datetime.datetime.now() - if now - datetime.timedelta(seconds=3) > previous: - previous = datetime.datetime.now() - x, y = env.get_position() - checkpoints.append( - [ - len(checkpoints), - (x, y), - datetime.datetime.now().strftime("%M:%S.%f")[-4], - ] - ) - - if ( - datetime.datetime.now() - datetime.timedelta(minutes=3, seconds=12) - > start_time - ): - print("Finish. Saving parameters . . .") - utils.save_times(checkpoints) - env.close() - exit(0) - - if not done: - state = nextState - else: - last_time_steps = np.append(last_time_steps, [int(step + 1)]) - stats[int(episode)] = step - states_reward[int(episode)] = cumulated_reward - print( - f"EP: {episode + 1} - epsilon: {round(qlearn.epsilon, 2)} - Reward: {cumulated_reward}" - f" - Time: {start_time_format} - Steps: {step}" - ) - break - - if step > estimate_step_per_lap and not lap_completed: - lap_completed = True - if config.plotter_graphic: - plotter.plot_steps_vs_epoch(stats, save=True) - utils.save_model( - qlearn, start_time_format, stats, states_counter, states_reward - ) - print( - f"\n\n====> LAP COMPLETED in: {datetime.datetime.now() - start_time} - Epoch: {episode}" - f" - Cum. Reward: {cumulated_reward} <====\n\n" - ) - - if counter > 1000: - if config.plotter_graphic: - plotter.plot_steps_vs_epoch(stats, save=True) - qlearn.epsilon *= epsilon_discount - utils.save_model( - qlearn, start_time_format, episode, states_counter, states_reward - ) - print( - f"\t- epsilon: {round(qlearn.epsilon, 2)}\n\t- cum reward: {cumulated_reward}\n\t- dict_size: " - f"{len(qlearn.q)}\n\t- time: {datetime.datetime.now()-start_time}\n\t- steps: {step}\n" - ) - counter = 0 - - if datetime.datetime.now() - datetime.timedelta(hours=2) > start_time: - print(config.eop) - utils.save_model( - qlearn, start_time_format, stats, states_counter, states_reward - ) - print(f" - N epoch: {episode}") - print(f" - Model size: {len(qlearn.q)}") - print(f" - Action set: {config.actions_set}") - print(f" - Epsilon: {round(qlearn.epsilon, 2)}") - print(f" - Cum. reward: {cumulated_reward}") - - env.close() - exit(0) - - if episode % 1 == 0 and config.plotter_graphic: - # plotter.plot(env) - plotter.plot_steps_vs_epoch(stats) - # plotter.full_plot(env, stats, 2) # optional parameter = mode (0, 1, 2) - - if episode % 250 == 0 and config.save_model and episode > 1: - print(f"\nSaving model . . .\n") - utils.save_model( - qlearn, start_time_format, stats, states_counter, states_reward - ) - - m, s = divmod(int(time.time() - telemetry_start_time), 60) - h, m = divmod(m, 60) - - print( - "Total EP: {} - epsilon: {} - ep. discount: {} - Highest Reward: {}".format( - total_episodes, initial_epsilon, epsilon_discount, highest_reward - ) - ) - - l = last_time_steps.tolist() - l.sort() - - # print("Parameters: a="+str) - print("Overall score: {:0.2f}".format(last_time_steps.mean())) - print( - "Best 100 score: {:0.2f}".format( - reduce(lambda x, y: x + y, l[-100:]) / len(l[-100:]) - ) - ) - - plotter.plot_steps_vs_epoch(stats, save=True) - - env.close() - - -if __name__ == "__main__": - main() diff --git a/rl_studio/agents/f1/brains/manual_pilot.py b/rl_studio/agents/f1/manual_pilot.py similarity index 100% rename from rl_studio/agents/f1/brains/manual_pilot.py rename to rl_studio/agents/f1/manual_pilot.py diff --git a/rl_studio/agents/f1/settings.py b/rl_studio/agents/f1/settings.py index a9c0bad94..c9b7e8238 100644 --- a/rl_studio/agents/f1/settings.py +++ b/rl_studio/agents/f1/settings.py @@ -1,7 +1,6 @@ ########################### # Global variables file ########################### - from pydantic import BaseModel @@ -18,160 +17,7 @@ class QLearnConfig(BaseModel): output_dir = "./logs/qlearn_models/qlearn_camera_solved/" poi = 1 # The original pixel row is: 250, 300, 350, 400 and 450 but we work only with the half of the image actions_set = "simple" # test, simple, medium, hard - - if poi == 1: - x_row = [60] - elif poi == 2: - x_row = [60, 110] - elif poi == 3: - x_row = [10, 60, 110] # The first and last element is not used. Just for metrics - elif poi == 5: - x_row = [250, 300, 350, 400, 450] - - algorithm_params = { - "alpha": 0.2, - "gamma": 0.9, - "epsilon": 0.05, - "highest_reward": 4000, - } - - # === ACTIONS === (lineal, angular) - AVAILABLE_ACTIONS = { - "simple": {0: (3, 0), 1: (2, 1), 2: (2, -1)}, - "medium": { - 0: (3, 0), - 1: (2, 1), - 2: (2, -1), - 3: (1, 1.5), - 4: (1, -1.5), - }, - "hard": { - 0: (3, 0), - 1: (2, 1), - 2: (2, -1), - 3: (1.5, 1), - 4: (1.5, -1), - 5: (1, 1.5), - 6: (1, -1.5), - }, - "test": { - 0: (0, 0), - }, - } - - # === GAZEBO POSITIONS === x, y, z, roll, pith, ???. yaw - GAZEBO_POSITIONS = { - "simple": [ - (0, 53.462, -41.988, 0.004, 0, 0, 1.57, -1.57), - (1, 53.462, -8.734, 0.004, 0, 0, 1.57, -1.57), - (2, 39.712, -30.741, 0.004, 0, 0, 1.56, 1.56), - (3, -6.861, -36.481, 0.004, 0, 0.01, -0.858, 0.613), - (4, 20.043, 37.130, 0.003, 0, 0.103, -1.4383, -1.4383), - ], - "nurburgring": [ - (0, -32.3188, 12.2921, 0, 0.0014, 0.0049, -0.2727, 0.9620), - (1, -30.6566, -21.4929, 0, 0.0014, 0.0049, -0.4727, 0.8720), - (2, 28.0352, -17.7923, 0, 0.0001, 0.0051, -0.028, 1), - (3, 88.7408, -31.7120, 0, 0.0030, 0.0041, -0.1683, 0.98), - (4, -73.2172, 11.8508, 0, 0.0043, -0.0027, 0.8517, 0.5173), - (5, -73.6672, 37.4308, 0, 0.0043, -0.0027, 0.8517, 0.5173), - ], - "montreal": [ - (0, -201.88, -91.02, 0, 0.00, 0.001, 0.98, -0.15), - (1, -278.71, -95.50, 0, 0.00, 0.001, 1, 0.03), - (2, -272.93, -17.70, 0, 0.0001, 0.001, 0.48, 0.87), - (3, -132.73, 55.82, 0, 0.0030, 0.0041, -0.02, 0.9991), - (4, 294.99, 91.54, 0, 0.0043, -0.0027, 0.14, 0.99), - ], - } - - # === CIRCUIT === - envs_params = { - "simple": { - "env": "F1Env-v0", - "training_type": "qlearn_camera", - "circuit_name": "simple", - "actions": AVAILABLE_ACTIONS[actions_set], - "launch": "simple_circuit.launch", - "gaz_pos": GAZEBO_POSITIONS["simple"], - "start_pose": [ - GAZEBO_POSITIONS["simple"][1][1], - GAZEBO_POSITIONS["simple"][1][2], - ], - "alternate_pose": True, - "estimated_steps": 4000, - "sensor": "camera", - }, - "nurburgring": { - "env": "F1Env-v0", - "training_type": "qlearn_camera", - "circuit_name": "nurburgring", - "actions": AVAILABLE_ACTIONS[actions_set], - "launch": "nurburgring_line.launch", - "gaz_pos": GAZEBO_POSITIONS["nurburgring"], - "start_pose": [ - GAZEBO_POSITIONS["nurburgring"][5][1], - GAZEBO_POSITIONS["nurburgring"][5][2], - ], - "alternate_pose": True, - "estimated_steps": 3500, - "sensor": "camera", - }, - "montreal": { - "env": "F1Env-v0", - "training_type": "qlearn_camera", - "circuit_name": "montreal", - "actions": AVAILABLE_ACTIONS[actions_set], - "launch": "montreal_line.launch", - "gaz_pos": GAZEBO_POSITIONS["montreal"], - "start_pose": [ - GAZEBO_POSITIONS["montreal"][0][1], - GAZEBO_POSITIONS["montreal"][0][2], - ], - "alternate_pose": False, - "estimated_steps": 8000, - "sensor": "camera", - }, - "curves": { - "env": "F1Env-v0", - "training_type": "qlearn_camera", - "circuit_name": "curves", - "actions": AVAILABLE_ACTIONS[actions_set], - "launch": "many_curves.launch", - "gaz_pos": "", - "alternate_pose": False, - "sensor": "camera", - }, - "simple_laser": { - "env": "F1Env-v0", - "training_type": "qlearn_laser", - "circuit_name": "montreal", - "actions": AVAILABLE_ACTIONS[actions_set], - "launch": "f1_montreal.launch", - "gaz_pos": "", - "start_pose": "", - "alternate_pose": False, - "sensor": "laser", - }, - "manual": { - "env": "F1Env-v0", - "training_type": "manual", - "circuit_name": "simple", - "actions": AVAILABLE_ACTIONS[actions_set], - "launch": "simple_circuit.launch", - "gaz_pos": "", - "start_pose": [ - GAZEBO_POSITIONS["nurburgring"][5][1], - GAZEBO_POSITIONS["nurburgring"][5][2], - ], - "alternate_pose": False, - "estimated_steps": 3000, - "sensor": "camera", - }, - } - max_distance = 0.5 - # === CAMERA === # Images size width = 640 @@ -182,6 +28,14 @@ class QLearnConfig(BaseModel): ranges = [300, 280, 250] # Line 1, 2 and 3 reset_range = [-40, 40] last_center_line = 0 + if poi == 1: + x_row = [60] + elif poi == 2: + x_row = [60, 110] + elif poi == 3: + x_row = [10, 60, 110] # The first and last element is not used. Just for metrics + elif poi == 5: + x_row = [250, 300, 350, 400, 450] qlearn = QLearnConfig() diff --git a/rl_studio/agents/f1/brains/train_dqn.py b/rl_studio/agents/f1/train_dqn.py similarity index 100% rename from rl_studio/agents/f1/brains/train_dqn.py rename to rl_studio/agents/f1/train_dqn.py diff --git a/rl_studio/agents/f1/train_qlearn.py b/rl_studio/agents/f1/train_qlearn.py new file mode 100755 index 000000000..783f08c66 --- /dev/null +++ b/rl_studio/agents/f1/train_qlearn.py @@ -0,0 +1,229 @@ +import datetime +import time +from functools import reduce +from pprint import pprint + +import gym +import numpy as np + +from agents import utils, liveplot +from algorithms.qlearn import QLearn +from rl_studio.agents.f1.settings import QLearnConfig +from rl_studio.visual.ascii.images import JDEROBOT_LOGO +from rl_studio.visual.ascii.text import JDEROBOT, QLEARN_CAMERA, LETS_GO + + +class F1Trainer: + + def __init__(self, params): + # TODO: Create a pydantic metaclass to simplify the way we extract the params + # environment params + self.environment_params = params.environment["params"] + self.env_name = params.environment["params"]["env_name"] + env_params = params.environment["params"] + actions = params.environment["actions"] + env_params["actions"] = actions + self.env = gym.make(self.env_name, **env_params) + # algorithm params + self.alpha = params.algorithm["params"]["alpha"] + self.epsilon = params.algorithm["params"]["epsilon"] + self.gamma = params.algorithm["params"]["gamma"] + # agent + # self.action_number = params.agent["params"]["actions_number"] + # self.actions_set = params.agent["params"]["actions_set"] + # self.actions_values = params.agent["params"]["available_actions"][self.actions_set] + + def main(self): + + print(JDEROBOT) + print(JDEROBOT_LOGO) + print(QLEARN_CAMERA) + print(f"\t- Start hour: {datetime.datetime.now()}\n") + pprint(f"\t- Environment params:\n{self.environment_params}", indent=4) + config = QLearnConfig() + + # TODO: Move init method + outdir = "./logs/f1_qlearn_gym_experiments/" + stats = {} # epoch: steps + states_counter = {} + states_reward = {} + + plotter = liveplot.LivePlot(outdir) + + last_time_steps = np.ndarray(0) + + actions = range(3) # range(env.action_space.n) + env = gym.wrappers.Monitor(self.env, outdir, force=True) + counter = 0 + estimate_step_per_lap = self.environment_params["estimated_steps"] + lap_completed = False + total_episodes = 20000 + epsilon_discount = 0.9986 # Default 0.9986 + + # TODO: Call the algorithm factory passing "qlearn" as parameter. + qlearn = QLearn(actions=actions, alpha=self.alpha, gamma=0.9, epsilon=0.99) + + if config.load_model: + # TODO: Folder to models. Maybe from environment variable? + file_name = "" + utils.load_model(qlearn, file_name) + highest_reward = max(qlearn.q.values(), key=stats.get) + else: + highest_reward = 0 + initial_epsilon = qlearn.epsilon + + telemetry_start_time = time.time() + start_time = datetime.datetime.now() + start_time_format = start_time.strftime("%Y%m%d_%H%M") + + print(LETS_GO) + + previous = datetime.datetime.now() + checkpoints = [] # "ID" - x, y - time + + # START + for episode in range(total_episodes): + + counter = 0 + done = False + lap_completed = False + + cumulated_reward = 0 + observation = env.reset() + + if qlearn.epsilon > 0.05: + qlearn.epsilon *= epsilon_discount + + state = "".join(map(str, observation)) + + for step in range(500000): + + counter += 1 + + # Pick an action based on the current state + action = qlearn.selectAction(state) + + # Execute the action and get feedback + observation, reward, done, info = env.step(action) + cumulated_reward += reward + + if highest_reward < cumulated_reward: + highest_reward = cumulated_reward + + nextState = "".join(map(str, observation)) + + try: + states_counter[nextState] += 1 + except KeyError: + states_counter[nextState] = 1 + + qlearn.learn(state, action, reward, nextState) + + env._flush(force=True) + + if config.save_positions: + now = datetime.datetime.now() + if now - datetime.timedelta(seconds=3) > previous: + previous = datetime.datetime.now() + x, y = env.get_position() + checkpoints.append( + [ + len(checkpoints), + (x, y), + datetime.datetime.now().strftime("%M:%S.%f")[-4], + ] + ) + + if ( + datetime.datetime.now() - datetime.timedelta(minutes=3, seconds=12) + > start_time + ): + print("Finish. Saving parameters . . .") + utils.save_times(checkpoints) + env.close() + exit(0) + + if not done: + state = nextState + else: + last_time_steps = np.append(last_time_steps, [int(step + 1)]) + stats[int(episode)] = step + states_reward[int(episode)] = cumulated_reward + print( + f"EP: {episode + 1} - epsilon: {round(qlearn.epsilon, 2)} - Reward: {cumulated_reward}" + f" - Time: {start_time_format} - Steps: {step}" + ) + break + + if step > estimate_step_per_lap and not lap_completed: + lap_completed = True + if config.plotter_graphic: + plotter.plot_steps_vs_epoch(stats, save=True) + utils.save_model( + qlearn, start_time_format, stats, states_counter, states_reward + ) + print( + f"\n\n====> LAP COMPLETED in: {datetime.datetime.now() - start_time} - Epoch: {episode}" + f" - Cum. Reward: {cumulated_reward} <====\n\n" + ) + + if counter > 1000: + if config.plotter_graphic: + plotter.plot_steps_vs_epoch(stats, save=True) + qlearn.epsilon *= epsilon_discount + utils.save_model( + qlearn, start_time_format, episode, states_counter, states_reward + ) + print( + f"\t- epsilon: {round(qlearn.epsilon, 2)}\n\t- cum reward: {cumulated_reward}\n\t- dict_size: " + f"{len(qlearn.q)}\n\t- time: {datetime.datetime.now()-start_time}\n\t- steps: {step}\n" + ) + counter = 0 + + if datetime.datetime.now() - datetime.timedelta(hours=2) > start_time: + print(config.eop) + utils.save_model( + qlearn, start_time_format, stats, states_counter, states_reward + ) + print(f" - N epoch: {episode}") + print(f" - Model size: {len(qlearn.q)}") + print(f" - Action set: {config.actions_set}") + print(f" - Epsilon: {round(qlearn.epsilon, 2)}") + print(f" - Cum. reward: {cumulated_reward}") + + env.close() + exit(0) + + if episode % 1 == 0 and config.plotter_graphic: + # plotter.plot(env) + plotter.plot_steps_vs_epoch(stats) + # plotter.full_plot(env, stats, 2) # optional parameter = mode (0, 1, 2) + + if episode % 250 == 0 and config.save_model and episode > 1: + print(f"\nSaving model . . .\n") + utils.save_model( + qlearn, start_time_format, stats, states_counter, states_reward + ) + + m, s = divmod(int(time.time() - telemetry_start_time), 60) + h, m = divmod(m, 60) + + print( + "Total EP: {} - epsilon: {} - ep. discount: {} - Highest Reward: {}".format( + total_episodes, initial_epsilon, epsilon_discount, highest_reward + ) + ) + + l = last_time_steps.tolist() + l.sort() + + print("Overall score: {:0.2f}".format(last_time_steps.mean())) + print( + "Best 100 score: {:0.2f}".format( + reduce(lambda x, y: x + y, l[-100:]) / len(l[-100:]) + ) + ) + + plotter.plot_steps_vs_epoch(stats, save=True) + + env.close() diff --git a/rl_studio/agents/f1/liveplot.py b/rl_studio/agents/liveplot.py similarity index 100% rename from rl_studio/agents/f1/liveplot.py rename to rl_studio/agents/liveplot.py diff --git a/rl_studio/agents/f1/ros_gazebo_pose.py b/rl_studio/agents/ros_gazebo_pose.py similarity index 100% rename from rl_studio/agents/f1/ros_gazebo_pose.py rename to rl_studio/agents/ros_gazebo_pose.py diff --git a/rl_studio/agents/trainer.py b/rl_studio/agents/trainer.py new file mode 100644 index 000000000..9f801eb4c --- /dev/null +++ b/rl_studio/agents/trainer.py @@ -0,0 +1,15 @@ +from abc import ABC + +from pydantic import BaseModel + + +class TrainerValidator(BaseModel): + settings: dict + agent: dict + environment: dict + algorithm: dict + # gazebo: dict + + +class AgentTrainer(ABC): + pass diff --git a/rl_studio/agents/turtlebot/turtlebot_trainer.py b/rl_studio/agents/turtlebot/turtlebot_trainer.py new file mode 100644 index 000000000..7b5eb98be --- /dev/null +++ b/rl_studio/agents/turtlebot/turtlebot_trainer.py @@ -0,0 +1,3 @@ +class TurtlebotTrainer: + def __init__(self, params): + pass diff --git a/rl_studio/agents/f1/utils.py b/rl_studio/agents/utils.py similarity index 100% rename from rl_studio/agents/f1/utils.py rename to rl_studio/agents/utils.py diff --git a/rl_studio/algorithms/__init__.py b/rl_studio/algorithms/__init__.py index e69de29bb..a28e516c7 100644 --- a/rl_studio/algorithms/__init__.py +++ b/rl_studio/algorithms/__init__.py @@ -0,0 +1,6 @@ + + +class TrainerFactory: + def __init__(self, **kwargs): + self.algorithm = kwargs.get("algorithm") + diff --git a/rl_studio/agents/f1/brains/__init__.py b/rl_studio/algorithms/models/__init__.py similarity index 100% rename from rl_studio/agents/f1/brains/__init__.py rename to rl_studio/algorithms/models/__init__.py diff --git a/rl_studio/algorithms/models/qlearn.py b/rl_studio/algorithms/models/qlearn.py new file mode 100644 index 000000000..e4a3bca6d --- /dev/null +++ b/rl_studio/algorithms/models/qlearn.py @@ -0,0 +1,9 @@ +from pydantic import BaseModel + + +class QlearnValidator(BaseModel): + alpha: float + epsilon: float + gamma: float + # actions_set: str = "simple" + # available_actions: dict diff --git a/rl_studio/algorithms/qlearn.py b/rl_studio/algorithms/qlearn.py index 3e82c86a9..6bed44302 100755 --- a/rl_studio/algorithms/qlearn.py +++ b/rl_studio/algorithms/qlearn.py @@ -6,7 +6,7 @@ class QLearn: - def __init__(self, actions, epsilon, alpha, gamma): + def __init__(self, actions, epsilon=0.99, alpha=0.8, gamma=0.9): self.q = {} self.epsilon = epsilon # exploration constant self.alpha = alpha # discount constant diff --git a/rl_studio/config.yaml b/rl_studio/config.yaml new file mode 100644 index 000000000..bb9040b95 --- /dev/null +++ b/rl_studio/config.yaml @@ -0,0 +1,125 @@ +settings: + output_dir: "./logs/" + save_model: True + save_positions: True + debug_level: DEBUG + telemetry: False + +agent: + f1: + camera_params: + witdh: 640 + height: 480 + +actions: + actions_number: 3 + actions_set: simple + available_actions: + # [lineal, angular] + simple: + 0: [ 3, 0 ] + 1: [ 2, 1 ] + 2: [ 2, -1 ] + medium: + 0: [ 3, 0 ] + 1: [ 2, 1 ] + 2: [ 2, -1 ] + 3: [ 1, 1.5 ] + 4: [ 1, -1.5 ] + hard: + 0: [ 3, 0 ] + 1: [ 2, 1 ] + 2: [ 2, -1 ] + 3: [ 1.5, 1 ] + 4: [ 1.5, -1 ] + 5: [ 1, -1.5 ] + 6: [ 1, -1.5 ] + test: + 0: [ 0, 0 ] + + +environments: + simple: + env_name: F1Env-v0 + circuit_name: simple + training_type: qlearn_camera + launch: simple_circuit.launch + start_pose: 0 + alternate_pose: True + estimated_steps: 4000 + sensor: camera + circuit_positions_set: # x, y, z, roll, pith, ???. yaw + - [ 0, 53.462, -41.988, 0.004, 0, 0, 1.57, -1.57 ] + - [ 1, 53.462, -8.734, 0.004, 0, 0, 1.57, -1.57 ] + - [ 2, 39.712, -30.741, 0.004, 0, 0, 1.56, 1.56 ] + - [ 3, -6.861, -36.481, 0.004, 0, 0.01, -0.858, 0.613 ] + - [ 4, 20.043, 37.130, 0.003, 0, 0.103, -1.4383, -1.4383 ] + nurburgring: + env_name: F1Env-v0 + circuit_name: nurburgring + training_type: qlearn_camera + launch: nurburgring_line.launch + start_pose: 0 + alternate_pose: True + estimated_steps: 3500 + sensor: camera + circuit_positions_set: # x, y, z, roll, pith, ???. yaw + - [ 0, -32.3188, 12.2921, 0, 0.0014, 0.0049, -0.2727, 0.9620 ] + - [ 1, -30.6566, -21.4929, 0, 0.0014, 0.0049, -0.4727, 0.8720 ] + - [ 2, 28.0352, -17.7923, 0, 0.0001, 0.0051, -0.028, 1 ] + - [ 3, 88.7408, -31.7120, 0, 0.0030, 0.0041, -0.1683, 0.98 ] + - [ 4, -73.2172, 11.8508, 0, 0.0043, -0.0027, 0.8517, 0.5173 ] + - [ 5, -73.6672, 37.4308, 0, 0.0043, -0.0027, 0.8517, 0.5173 ] + montreal: + env_name: F1Env-v0 + circuit_name: montreal + training_type: qlearn_camera + launch: montreal_line.launch + start_pose: 0 + alternate_pose: True + estimated_steps: 8000 + sensor: camera + circuit_positions_set: # x, y, z, roll, pith, ???. yaw + - [0, -201.88, -91.02, 0, 0.00, 0.001, 0.98, -0.15] + - [1, -278.71, -95.50, 0, 0.00, 0.001, 1, 0.03] + - [2, -272.93, -17.70, 0, 0.0001, 0.001, 0.48, 0.87] + - [3, -132.73, 55.82, 0, 0.0030, 0.0041, -0.02, 0.9991] + - [4, 294.99, 91.54, 0, 0.0043, -0.0027, 0.14, 0.99] + curves: + env_name: F1Env-v0 + circuit_name: curves + training_type: qlearn_camera + launch: many_curves.launch + start_pose: 0 + alternate_pose: False + estimated_steps: 4000 + sensor: camera + simple_laser: + env_name: F1Env-v0 + circuit_name: simple_laser + training_type: qlearn_laser + launch: f1_montreal.launch + start_pose: 0 + alternate_pose: False + estimated_steps: 4000 + sensor: laser + manual: + env_name: F1Env-v0 + circuit_name: manual + training_type: qlearn_camera + launch: simple_circuit.launch + start_pose: 0 + alternate_pose: False + estimated_steps: 4000 + sensor: camera + + +algorithm: + qlearn: + alpha: 0.2 + epsilon: 0.95 + gamma: 0.9 + + dqn: + + sarsa: diff --git a/rl_studio/docs/rlstudio-diagram.excalidraw b/rl_studio/docs/rlstudio-diagram.excalidraw new file mode 100644 index 000000000..e14f9fec0 --- /dev/null +++ b/rl_studio/docs/rlstudio-diagram.excalidraw @@ -0,0 +1,2455 @@ +{ + "type": "excalidraw", + "version": 2, + "source": "https://excalidraw.com", + "elements": [ + { + "id": "so8UXkj9nhsVv7gbekxQC", + "type": "rectangle", + "x": 1327, + "y": 528, + "width": 134.99999999999997, + "height": 81, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#fa5252", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 2011900523, + "version": 224, + "versionNonce": 1505557445, + "isDeleted": false, + "boundElements": [ + { + "id": "EtLiZhEZaa9WLgzibOC4Z", + "type": "arrow" + }, + { + "id": "qG81XyLuPfPbdcDtHu51L", + "type": "arrow" + }, + { + "id": "LPsjeogUdX7U8ypC58mA_", + "type": "arrow" + }, + { + "id": "nOi6tq-2dNTSewXtFLShT", + "type": "arrow" + } + ], + "updated": 1642362303106 + }, + { + "type": "rectangle", + "version": 245, + "versionNonce": 1769295627, + "isDeleted": false, + "id": "iO4YUTo6wpPyvPrjSiH2E", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1501, + "y": 524, + "strokeColor": "#000000", + "backgroundColor": "#fd7e14", + "width": 159, + "height": 81.99999999999999, + "seed": 797132229, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [ + { + "id": "35gsK7a88pUj2QOJPFHu_", + "type": "arrow" + }, + { + "id": "ER8F9_6BgoPz74mJ_P0lE", + "type": "arrow" + }, + { + "id": "u95dSBtxdkYs1G4Xy6W6U", + "type": "arrow" + }, + { + "id": "T4pXRAYFkR-g6wcwWtdUi", + "type": "arrow" + } + ], + "updated": 1642362303106 + }, + { + "type": "rectangle", + "version": 196, + "versionNonce": 244529957, + "isDeleted": false, + "id": "6SO22MQMvMxyiJkOdh9pQ", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1691, + "y": 526, + "strokeColor": "#000000", + "backgroundColor": "#15aabf", + "width": 148, + "height": 83, + "seed": 1905304843, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [ + { + "id": "A75jfXlo10-Lm9-5tsORl", + "type": "arrow" + }, + { + "id": "zAqc0tOxaphg3HEg5nuwH", + "type": "arrow" + }, + { + "id": "F9PeeG-Mzjn5lnODx564W", + "type": "arrow" + }, + { + "id": "aHRyPPlRffPPgpnIeV9Dh", + "type": "arrow" + } + ], + "updated": 1642362303106 + }, + { + "id": "vK0ZH-nWppWFckecBqgSV", + "type": "text", + "x": 1356, + "y": 556, + "width": 67, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 687883557, + "version": 58, + "versionNonce": 1735346251, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303107, + "text": "agents", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 18, + "containerId": null, + "originalText": "agents" + }, + { + "id": "A1UUzvSFO4FjS0AIXQ3cR", + "type": "text", + "x": 1532, + "y": 551, + "width": 98, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 435014571, + "version": 102, + "versionNonce": 4224485, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303107, + "text": "algorithms", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 18, + "containerId": null, + "originalText": "algorithms" + }, + { + "id": "ZXl022mJeT83QTZu30d8r", + "type": "text", + "x": 1741, + "y": 552, + "width": 43, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 493246597, + "version": 78, + "versionNonce": 2056652523, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303107, + "text": "envs", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 18, + "containerId": null, + "originalText": "envs" + }, + { + "type": "rectangle", + "version": 259, + "versionNonce": 652374341, + "isDeleted": false, + "id": "HJhc_4H0EWQF6BPGBnwFZ", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1871.5, + "y": 525.5, + "strokeColor": "#000000", + "backgroundColor": "#fab005", + "width": 134.99999999999997, + "height": 81, + "seed": 355278411, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [ + { + "id": "YUVAzkQxTEOjO8Y5NnMjJ", + "type": "arrow" + }, + { + "id": "E2os0JITN7iIRJyipXLW9", + "type": "arrow" + }, + { + "id": "7gg0nm6qTBiIHxTYo0xmh", + "type": "arrow" + }, + { + "id": "N5ZV2DWnenzr6l09eCVY_", + "type": "arrow" + } + ], + "updated": 1642362303107 + }, + { + "type": "text", + "version": 106, + "versionNonce": 61600139, + "isDeleted": false, + "id": "7ON6HizTKJ76Qww8aECJp", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1900.5, + "y": 553.5, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "width": 68, + "height": 25, + "seed": 1987248101, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [], + "updated": 1642362303107, + "fontSize": 20, + "fontFamily": 1, + "text": "gazebo", + "baseline": 18, + "textAlign": "left", + "verticalAlign": "top", + "containerId": null, + "originalText": "gazebo" + }, + { + "type": "rectangle", + "version": 256, + "versionNonce": 1382940837, + "isDeleted": false, + "id": "WTDldziLTtQz8IskT5HTT", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1596.5, + "y": 348.5, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "width": 134.99999999999997, + "height": 81, + "seed": 1609171269, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [ + { + "id": "7tmiLF0VuxWnTf665kBe4", + "type": "arrow" + }, + { + "id": "qG81XyLuPfPbdcDtHu51L", + "type": "arrow" + }, + { + "id": "ER8F9_6BgoPz74mJ_P0lE", + "type": "arrow" + }, + { + "id": "zAqc0tOxaphg3HEg5nuwH", + "type": "arrow" + }, + { + "id": "E2os0JITN7iIRJyipXLW9", + "type": "arrow" + } + ], + "updated": 1642362303107 + }, + { + "type": "text", + "version": 100, + "versionNonce": 1407944747, + "isDeleted": false, + "id": "j7BUxHy2lXxvGtE7YQAHD", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1625.5, + "y": 376.5, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "width": 65, + "height": 25, + "seed": 1822777739, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [], + "updated": 1642362303107, + "fontSize": 20, + "fontFamily": 1, + "text": "main.py", + "baseline": 18, + "textAlign": "left", + "verticalAlign": "top", + "containerId": null, + "originalText": "main.py" + }, + { + "type": "rectangle", + "version": 301, + "versionNonce": 1485874181, + "isDeleted": false, + "id": "3RSbd5N9EYa6ANcIBZyMO", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1791.5, + "y": 269.5, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "width": 135, + "height": 81, + "seed": 551379563, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [ + { + "type": "text", + "id": "y0Rb-C9dhpsFXVuA_lF8T" + }, + { + "id": "7tmiLF0VuxWnTf665kBe4", + "type": "arrow" + } + ], + "updated": 1642362303107 + }, + { + "id": "y0Rb-C9dhpsFXVuA_lF8T", + "type": "text", + "x": 1796.5, + "y": 297.5, + "width": 125, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 212987429, + "version": 18, + "versionNonce": 826231499, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303107, + "text": "config.yml", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "center", + "verticalAlign": "middle", + "baseline": 18, + "containerId": "3RSbd5N9EYa6ANcIBZyMO", + "originalText": "config.yml" + }, + { + "id": "7tmiLF0VuxWnTf665kBe4", + "type": "arrow", + "x": 1861, + "y": 364, + "width": 119, + "height": 35, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 462649707, + "version": 94, + "versionNonce": 2101861221, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303107, + "points": [ + [ + 0, + 0 + ], + [ + -119, + 35 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "3RSbd5N9EYa6ANcIBZyMO", + "focus": -0.9044834307992203, + "gap": 13.5 + }, + "endBinding": { + "elementId": "WTDldziLTtQz8IskT5HTT", + "focus": 0.5458089668615984, + "gap": 10.5 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "hcWDkGa9IyQAOaXZQ37ye", + "type": "line", + "x": 1215, + "y": 648, + "width": 917, + "height": 0, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "dashed", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 172715717, + "version": 59, + "versionNonce": 1870657925, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303108, + "points": [ + [ + 0, + 0 + ], + [ + 917, + 0 + ] + ], + "lastCommittedPoint": null, + "startBinding": null, + "endBinding": null, + "startArrowhead": null, + "endArrowhead": null + }, + { + "id": "snfJdXezqe9tg9PCEzYG4", + "type": "text", + "x": 1134, + "y": 531, + "width": 143, + "height": 70, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "dashed", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 397952299, + "version": 101, + "versionNonce": 1136266571, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303108, + "text": "parameter\nacquisition", + "fontSize": 28, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 60, + "containerId": null, + "originalText": "parameter\nacquisition" + }, + { + "id": "rSLMGDDSANk39uZ1qSXoL", + "type": "rectangle", + "x": 1337, + "y": 977, + "width": 134.99999999999997, + "height": 81, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 1611274123, + "version": 449, + "versionNonce": 1481072869, + "isDeleted": false, + "boundElements": [ + { + "id": "EtLiZhEZaa9WLgzibOC4Z", + "type": "arrow" + }, + { + "id": "YocjEL2rruEGX5ZI6ib6m", + "type": "arrow" + }, + { + "id": "nOi6tq-2dNTSewXtFLShT", + "type": "arrow" + }, + { + "id": "CrWnLffoEmAxN3TSlmMyw", + "type": "arrow" + }, + { + "id": "N1L85R55MwKBC9PzLPGcz", + "type": "arrow" + }, + { + "id": "jN4UYAnktnV_Yw60T3IFj", + "type": "arrow" + }, + { + "id": "WpRWj4wsphy5Bnq8oAztK", + "type": "arrow" + }, + { + "id": "SzngLEi5fMuV4BAB1hUpH", + "type": "arrow" + }, + { + "id": "6Mqoc3CUC1kDXW-H8PnXC", + "type": "arrow" + }, + { + "id": "C56y13xv1mZB0LD6qFnq7", + "type": "arrow" + } + ], + "updated": 1642362478360 + }, + { + "type": "rectangle", + "version": 464, + "versionNonce": 1423178821, + "isDeleted": false, + "id": "iQff4S2v-YJgbx7HyTt9e", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1511, + "y": 973, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "width": 159, + "height": 81.99999999999999, + "seed": 1272732645, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [ + { + "id": "35gsK7a88pUj2QOJPFHu_", + "type": "arrow" + }, + { + "id": "_TTgQHgDVPVk6emSAJD2b", + "type": "arrow" + }, + { + "id": "T4pXRAYFkR-g6wcwWtdUi", + "type": "arrow" + }, + { + "id": "G--IIfKHDfN5v238FEhKJ", + "type": "arrow" + }, + { + "id": "C56y13xv1mZB0LD6qFnq7", + "type": "arrow" + } + ], + "updated": 1642362478361 + }, + { + "type": "rectangle", + "version": 416, + "versionNonce": 1878377707, + "isDeleted": false, + "id": "AlPYVihubZCxJQk7pB7yt", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1701, + "y": 975, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "width": 148, + "height": 83, + "seed": 865304811, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [ + { + "id": "A75jfXlo10-Lm9-5tsORl", + "type": "arrow" + }, + { + "id": "wOzoa7Y2iPECskRDHJKx9", + "type": "arrow" + }, + { + "id": "aHRyPPlRffPPgpnIeV9Dh", + "type": "arrow" + }, + { + "id": "Mb0iRSRUFKwoit6vzjK8N", + "type": "arrow" + }, + { + "id": "jN4UYAnktnV_Yw60T3IFj", + "type": "arrow" + }, + { + "id": "SzngLEi5fMuV4BAB1hUpH", + "type": "arrow" + } + ], + "updated": 1642362422507 + }, + { + "id": "ChyaIGAhCl5VZZgLawhEu", + "type": "text", + "x": 1396, + "y": 1006, + "width": 16, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 1233829605, + "version": 290, + "versionNonce": 781667237, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303108, + "text": "f1", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 18, + "containerId": null, + "originalText": "f1" + }, + { + "id": "uk8-OqwXIEYFoNb-2x7EP", + "type": "text", + "x": 1567, + "y": 1003, + "width": 59, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 228446149, + "version": 347, + "versionNonce": 571501867, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303109, + "text": "qlearn", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 18, + "containerId": null, + "originalText": "qlearn" + }, + { + "id": "cNpNqZIRlhvi3rB_pJvng", + "type": "text", + "x": 1743, + "y": 1002, + "width": 70, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 1377775461, + "version": 314, + "versionNonce": 391679749, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303109, + "text": "camera", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 18, + "containerId": null, + "originalText": "camera" + }, + { + "type": "rectangle", + "version": 478, + "versionNonce": 825971371, + "isDeleted": false, + "id": "wI0GlFUuLqB8Tx5Wyp0q_", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1881.5, + "y": 974.5, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "width": 134.99999999999997, + "height": 81, + "seed": 1201744363, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [ + { + "id": "YUVAzkQxTEOjO8Y5NnMjJ", + "type": "arrow" + }, + { + "id": "0-L_4LMjCC6UP3gkUVgQE", + "type": "arrow" + }, + { + "id": "N5ZV2DWnenzr6l09eCVY_", + "type": "arrow" + }, + { + "id": "TI9Bg9CwR-dC1ybGfrtJw", + "type": "arrow" + }, + { + "id": "WpRWj4wsphy5Bnq8oAztK", + "type": "arrow" + } + ], + "updated": 1642362410479 + }, + { + "type": "text", + "version": 337, + "versionNonce": 299525733, + "isDeleted": false, + "id": "yajoyN7AXI27BdrcyyeCa", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "angle": 0, + "x": 1911.5, + "y": 1002.5, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "width": 85, + "height": 25, + "seed": 1573846597, + "groupIds": [], + "strokeSharpness": "sharp", + "boundElements": [], + "updated": 1642362303109, + "fontSize": 20, + "fontFamily": 1, + "text": "sim. conf", + "baseline": 18, + "textAlign": "left", + "verticalAlign": "top", + "containerId": null, + "originalText": "sim. conf" + }, + { + "id": "U-EKjQ2I8Nqp77fo0hFXS", + "type": "text", + "x": 1129, + "y": 723, + "width": 104, + "height": 35, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "dashed", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 2135632645, + "version": 160, + "versionNonce": 227457099, + "isDeleted": false, + "boundElements": [ + { + "id": "LUKsczhb4tA-FBj4UuVr_", + "type": "arrow" + }, + { + "id": "AnYN90VNUcVDpxC9ADTff", + "type": "arrow" + } + ], + "updated": 1642363291245, + "text": "factory", + "fontSize": 28, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 25, + "containerId": null, + "originalText": "factory" + }, + { + "id": "ame5KpH1huZ8Ub_T8uka_", + "type": "text", + "x": 1136, + "y": 624, + "width": 90, + "height": 50, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "dashed", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 1320986795, + "version": 147, + "versionNonce": 351970731, + "isDeleted": false, + "boundElements": [ + { + "id": "AnYN90VNUcVDpxC9ADTff", + "type": "arrow" + } + ], + "updated": 1642363291245, + "text": "trainer\nvalidator", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 43, + "containerId": null, + "originalText": "trainer\nvalidator" + }, + { + "id": "qG81XyLuPfPbdcDtHu51L", + "type": "arrow", + "x": 1656, + "y": 440, + "width": 263, + "height": 80, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 571833323, + "version": 48, + "versionNonce": 1160761931, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303110, + "points": [ + [ + 0, + 0 + ], + [ + -263, + 80 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "WTDldziLTtQz8IskT5HTT", + "focus": -0.7957511759025636, + "gap": 10.5 + }, + "endBinding": { + "elementId": "so8UXkj9nhsVv7gbekxQC", + "focus": -0.8021368719434322, + "gap": 8 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "ER8F9_6BgoPz74mJ_P0lE", + "type": "arrow", + "x": 1656, + "y": 440, + "width": 66, + "height": 70, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 1390811563, + "version": 45, + "versionNonce": 1143311333, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303110, + "points": [ + [ + 0, + 0 + ], + [ + -66, + 70 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "WTDldziLTtQz8IskT5HTT", + "focus": -0.3792917004595838, + "gap": 10.5 + }, + "endBinding": { + "elementId": "iO4YUTo6wpPyvPrjSiH2E", + "focus": -0.3584814411800267, + "gap": 14 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "zAqc0tOxaphg3HEg5nuwH", + "type": "arrow", + "x": 1654, + "y": 442, + "width": 106, + "height": 76, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 917952005, + "version": 27, + "versionNonce": 599085291, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303110, + "points": [ + [ + 0, + 0 + ], + [ + 106, + 76 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "WTDldziLTtQz8IskT5HTT", + "focus": 0.6768545049347342, + "gap": 12.5 + }, + "endBinding": { + "elementId": "6SO22MQMvMxyiJkOdh9pQ", + "focus": 0.48558315873490965, + "gap": 8 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "E2os0JITN7iIRJyipXLW9", + "type": "arrow", + "x": 1652, + "y": 439, + "width": 275, + "height": 74, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 1124910859, + "version": 37, + "versionNonce": 431277893, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303110, + "points": [ + [ + 0, + 0 + ], + [ + 275, + 74 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "WTDldziLTtQz8IskT5HTT", + "focus": 0.9073609174027585, + "gap": 9.5 + }, + "endBinding": { + "elementId": "HJhc_4H0EWQF6BPGBnwFZ", + "focus": 0.8484115915078259, + "gap": 12.5 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "t0VdGC-iBiarP2bozp1gL", + "type": "rectangle", + "x": 1572, + "y": 691, + "width": 187, + "height": 91, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#40c057", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 247845163, + "version": 83, + "versionNonce": 508689291, + "isDeleted": false, + "boundElements": [ + { + "id": "LPsjeogUdX7U8ypC58mA_", + "type": "arrow" + }, + { + "id": "F9PeeG-Mzjn5lnODx564W", + "type": "arrow" + }, + { + "id": "7gg0nm6qTBiIHxTYo0xmh", + "type": "arrow" + }, + { + "id": "YocjEL2rruEGX5ZI6ib6m", + "type": "arrow" + }, + { + "id": "_TTgQHgDVPVk6emSAJD2b", + "type": "arrow" + }, + { + "id": "wOzoa7Y2iPECskRDHJKx9", + "type": "arrow" + }, + { + "id": "0-L_4LMjCC6UP3gkUVgQE", + "type": "arrow" + }, + { + "id": "106Bw88m4zv4-EiFqNW_l", + "type": "arrow" + } + ], + "updated": 1642362303110 + }, + { + "id": "UcP15sOU_2wWeq0w9108z", + "type": "text", + "x": 1610, + "y": 698.5, + "width": 106, + "height": 70, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 416005125, + "version": 43, + "versionNonce": 20992555, + "isDeleted": false, + "boundElements": [ + { + "id": "u95dSBtxdkYs1G4Xy6W6U", + "type": "arrow" + } + ], + "updated": 1642362303110, + "text": "Trainer\nFactory", + "fontSize": 28, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 60, + "containerId": null, + "originalText": "Trainer\nFactory" + }, + { + "id": "LPsjeogUdX7U8ypC58mA_", + "type": "arrow", + "x": 1389.0000000000002, + "y": 612, + "width": 258.3033629065576, + "height": 73, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#fa5252", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 288211973, + "version": 47, + "versionNonce": 1866824197, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303110, + "points": [ + [ + 0, + 0 + ], + [ + 258.3033629065576, + 73 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "focus": 0.7672242134607726, + "gap": 3, + "elementId": "so8UXkj9nhsVv7gbekxQC" + }, + "endBinding": { + "focus": 0.7119316616147698, + "gap": 10, + "elementId": "t0VdGC-iBiarP2bozp1gL" + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "u95dSBtxdkYs1G4Xy6W6U", + "type": "arrow", + "x": 1589, + "y": 611, + "width": 75, + "height": 72, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#fa5252", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 1961291653, + "version": 36, + "versionNonce": 761976011, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303110, + "points": [ + [ + 0, + 0 + ], + [ + 75, + 72 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "iO4YUTo6wpPyvPrjSiH2E", + "focus": 0.3225366518922605, + "gap": 5 + }, + "endBinding": { + "elementId": "UcP15sOU_2wWeq0w9108z", + "focus": 0.5992081974848626, + "gap": 15.5 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "F9PeeG-Mzjn5lnODx564W", + "type": "arrow", + "x": 1757, + "y": 611, + "width": 86.62283608540565, + "height": 73, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#fa5252", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 802473349, + "version": 65, + "versionNonce": 1391587685, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303110, + "points": [ + [ + 0, + 0 + ], + [ + -86.62283608540565, + 73 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "focus": -0.35769838021168354, + "gap": 2, + "elementId": "6SO22MQMvMxyiJkOdh9pQ" + }, + "endBinding": { + "focus": -0.401153695737192, + "gap": 11, + "elementId": "t0VdGC-iBiarP2bozp1gL" + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "7gg0nm6qTBiIHxTYo0xmh", + "type": "arrow", + "x": 1939, + "y": 609, + "width": 242.74844357912684, + "height": 76, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#fa5252", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 929125221, + "version": 41, + "versionNonce": 40633195, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303110, + "points": [ + [ + 0, + 0 + ], + [ + -242.74844357912684, + 76 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "focus": -0.7048449009233323, + "gap": 2.5, + "elementId": "HJhc_4H0EWQF6BPGBnwFZ" + }, + "endBinding": { + "focus": -0.6009248950929178, + "gap": 10, + "elementId": "t0VdGC-iBiarP2bozp1gL" + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "G01uI8BSZIe0uxQjDohET", + "type": "rectangle", + "x": 1576, + "y": 835, + "width": 187, + "height": 91, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 1916845509, + "version": 182, + "versionNonce": 1377423237, + "isDeleted": false, + "boundElements": [ + { + "id": "LPsjeogUdX7U8ypC58mA_", + "type": "arrow" + }, + { + "id": "F9PeeG-Mzjn5lnODx564W", + "type": "arrow" + }, + { + "id": "7gg0nm6qTBiIHxTYo0xmh", + "type": "arrow" + }, + { + "id": "YocjEL2rruEGX5ZI6ib6m", + "type": "arrow" + }, + { + "id": "_TTgQHgDVPVk6emSAJD2b", + "type": "arrow" + }, + { + "id": "wOzoa7Y2iPECskRDHJKx9", + "type": "arrow" + }, + { + "id": "0-L_4LMjCC6UP3gkUVgQE", + "type": "arrow" + }, + { + "id": "106Bw88m4zv4-EiFqNW_l", + "type": "arrow" + }, + { + "id": "CrWnLffoEmAxN3TSlmMyw", + "type": "arrow" + }, + { + "id": "G--IIfKHDfN5v238FEhKJ", + "type": "arrow" + }, + { + "id": "Mb0iRSRUFKwoit6vzjK8N", + "type": "arrow" + }, + { + "id": "TI9Bg9CwR-dC1ybGfrtJw", + "type": "arrow" + } + ], + "updated": 1642362303111 + }, + { + "id": "dQe2SI1zlssz2YE7tmvan", + "type": "text", + "x": 1623, + "y": 866.5, + "width": 89, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "transparent", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 64196133, + "version": 73, + "versionNonce": 1402967781, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303111, + "text": "F1Trainer", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 18, + "containerId": null, + "originalText": "F1Trainer" + }, + { + "id": "nOi6tq-2dNTSewXtFLShT", + "type": "arrow", + "x": 1393.9913479151562, + "y": 622, + "width": 7.0165946349779915, + "height": 349, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "dotted", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 1663901003, + "version": 143, + "versionNonce": 1760916971, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303111, + "points": [ + [ + 0, + 0 + ], + [ + 7.0165946349779915, + 349 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "focus": 0.023191415714780207, + "gap": 13, + "elementId": "so8UXkj9nhsVv7gbekxQC" + }, + "endBinding": { + "focus": -0.03743262621767296, + "gap": 6, + "elementId": "rSLMGDDSANk39uZ1qSXoL" + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "106Bw88m4zv4-EiFqNW_l", + "type": "arrow", + "x": 1672, + "y": 791, + "width": 2, + "height": 38, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 1638576523, + "version": 48, + "versionNonce": 1672835653, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303111, + "points": [ + [ + 0, + 0 + ], + [ + -2, + 38 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "t0VdGC-iBiarP2bozp1gL", + "focus": -0.09769484083424806, + "gap": 9 + }, + "endBinding": { + "elementId": "G01uI8BSZIe0uxQjDohET", + "focus": -0.02305159165751921, + "gap": 6 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "T4pXRAYFkR-g6wcwWtdUi", + "type": "arrow", + "x": 1581.9913479151562, + "y": 620, + "width": 7.0165946349779915, + "height": 349, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "dotted", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 1740527397, + "version": 179, + "versionNonce": 1917157515, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303111, + "points": [ + [ + 0, + 0 + ], + [ + 7.0165946349779915, + 349 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "focus": -0.004800301487075316, + "gap": 14, + "elementId": "iO4YUTo6wpPyvPrjSiH2E" + }, + "endBinding": { + "focus": -0.0073120954758007445, + "gap": 4, + "elementId": "iQff4S2v-YJgbx7HyTt9e" + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "aHRyPPlRffPPgpnIeV9Dh", + "type": "arrow", + "x": 1769.9913479151562, + "y": 622, + "width": 7.0165946349779915, + "height": 349, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "dotted", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 588836133, + "version": 204, + "versionNonce": 1597563301, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303111, + "points": [ + [ + 0, + 0 + ], + [ + 7.0165946349779915, + 349 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "focus": -0.052056752033277594, + "gap": 13, + "elementId": "6SO22MQMvMxyiJkOdh9pQ" + }, + "endBinding": { + "focus": 0.03905577351718896, + "gap": 4, + "elementId": "AlPYVihubZCxJQk7pB7yt" + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "N5ZV2DWnenzr6l09eCVY_", + "type": "arrow", + "x": 1941.9913479151562, + "y": 620, + "width": 7.0165946349779915, + "height": 349, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "dotted", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 1463661765, + "version": 226, + "versionNonce": 1987786539, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303111, + "points": [ + [ + 0, + 0 + ], + [ + 7.0165946349779915, + 349 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "HJhc_4H0EWQF6BPGBnwFZ", + "focus": -0.027895875330943825, + "gap": 13.5 + }, + "endBinding": { + "elementId": "wI0GlFUuLqB8Tx5Wyp0q_", + "focus": 0.013654046665703985, + "gap": 5.5 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "CrWnLffoEmAxN3TSlmMyw", + "type": "arrow", + "x": 1662, + "y": 937, + "width": 239, + "height": 30, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 832193477, + "version": 44, + "versionNonce": 727147781, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303111, + "points": [ + [ + 0, + 0 + ], + [ + -239, + 30 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "G01uI8BSZIe0uxQjDohET", + "focus": -0.9706860630871011, + "gap": 11 + }, + "endBinding": { + "elementId": "rSLMGDDSANk39uZ1qSXoL", + "focus": -0.983766927250203, + "gap": 10 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "G--IIfKHDfN5v238FEhKJ", + "type": "arrow", + "x": 1662, + "y": 936, + "width": 48, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 864411301, + "version": 35, + "versionNonce": 1677793739, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303111, + "points": [ + [ + 0, + 0 + ], + [ + -48, + 25 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "G01uI8BSZIe0uxQjDohET", + "focus": -0.5477164657746323, + "gap": 10 + }, + "endBinding": { + "elementId": "iQff4S2v-YJgbx7HyTt9e", + "focus": -0.4946277335355835, + "gap": 12 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "Mb0iRSRUFKwoit6vzjK8N", + "type": "arrow", + "x": 1659, + "y": 936, + "width": 117, + "height": 28, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 1797354661, + "version": 26, + "versionNonce": 730758245, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303112, + "points": [ + [ + 0, + 0 + ], + [ + 117, + 28 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "G01uI8BSZIe0uxQjDohET", + "focus": 0.8546874016243782, + "gap": 10 + }, + "endBinding": { + "elementId": "AlPYVihubZCxJQk7pB7yt", + "focus": 0.8907253699025621, + "gap": 11 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "TI9Bg9CwR-dC1ybGfrtJw", + "type": "arrow", + "x": 1661, + "y": 936, + "width": 292, + "height": 30, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 236299531, + "version": 46, + "versionNonce": 2012325995, + "isDeleted": false, + "boundElements": null, + "updated": 1642362303112, + "points": [ + [ + 0, + 0 + ], + [ + 292, + 30 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "G01uI8BSZIe0uxQjDohET", + "focus": 1.0229942203716365, + "gap": 10 + }, + "endBinding": { + "elementId": "wI0GlFUuLqB8Tx5Wyp0q_", + "focus": 1.0416576420475057, + "gap": 8.5 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "WpRWj4wsphy5Bnq8oAztK", + "type": "arrow", + "x": 1484, + "y": 1072, + "width": 426, + "height": 74, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 955074923, + "version": 132, + "versionNonce": 282640773, + "isDeleted": false, + "boundElements": null, + "updated": 1642362410487, + "points": [ + [ + 0, + 0 + ], + [ + 48, + 47 + ], + [ + 169, + 74 + ], + [ + 258, + 65 + ], + [ + 358, + 41 + ], + [ + 426, + 0 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "rSLMGDDSANk39uZ1qSXoL", + "focus": -0.2189973614775726, + "gap": 14 + }, + "endBinding": { + "elementId": "wI0GlFUuLqB8Tx5Wyp0q_", + "focus": -0.4123879380603098, + "gap": 16.5 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "SzngLEi5fMuV4BAB1hUpH", + "type": "arrow", + "x": 1481, + "y": 1070, + "width": 309, + "height": 47, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 951266955, + "version": 206, + "versionNonce": 115708741, + "isDeleted": false, + "boundElements": null, + "updated": 1642362422519, + "points": [ + [ + 0, + 0 + ], + [ + 74, + 33 + ], + [ + 132, + 42 + ], + [ + 193, + 42 + ], + [ + 259, + 24 + ], + [ + 309, + -5 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "rSLMGDDSANk39uZ1qSXoL", + "focus": 0.26040769451622164, + "gap": 12 + }, + "endBinding": { + "elementId": "AlPYVihubZCxJQk7pB7yt", + "focus": -0.677564558161573, + "gap": 7 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "6Mqoc3CUC1kDXW-H8PnXC", + "type": "arrow", + "x": 1350.6904761904752, + "y": 1029.9285714285713, + "width": 61.428571428571104, + "height": 57.285714285714334, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 1727252011, + "version": 822, + "versionNonce": 1302135909, + "isDeleted": false, + "boundElements": null, + "updated": 1642362470518, + "points": [ + [ + 0, + 0 + ], + [ + 15.142857142857338, + 25.428571428571445 + ], + [ + 3.7857142857146755, + 48.57142857142844 + ], + [ + -15.714285714285325, + 56.571428571428555 + ], + [ + -41.21428571428578, + 44.5 + ], + [ + -46.285714285713766, + 25.28571428571422 + ], + [ + -26.999999999999545, + -0.7142857142857792 + ] + ], + "lastCommittedPoint": null, + "startBinding": null, + "endBinding": { + "elementId": "rSLMGDDSANk39uZ1qSXoL", + "focus": 0.7393834537053876, + "gap": 13.309523809524308 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "C56y13xv1mZB0LD6qFnq7", + "type": "arrow", + "x": 1476.4779855600796, + "y": 1067.8830747818163, + "width": 125, + "height": 17.5, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 567067051, + "version": 85, + "versionNonce": 262968971, + "isDeleted": false, + "boundElements": null, + "updated": 1642362478369, + "points": [ + [ + 0, + 0 + ], + [ + 65, + 17.5 + ], + [ + 125, + 0 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "rSLMGDDSANk39uZ1qSXoL", + "focus": 0.5284261195717249, + "gap": 9.883074781816276 + }, + "endBinding": { + "elementId": "iQff4S2v-YJgbx7HyTt9e", + "focus": -0.8893474155690672, + "gap": 12.883074781816276 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "G00cPo51SxZZjScTTmW6v", + "type": "text", + "x": 1143.9779855600796, + "y": 868.7164081151495, + "width": 77, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 2137554539, + "version": 61, + "versionNonce": 1734275045, + "isDeleted": false, + "boundElements": [ + { + "id": "LUKsczhb4tA-FBj4UuVr_", + "type": "arrow" + } + ], + "updated": 1642363279061, + "text": "creates", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 18, + "containerId": null, + "originalText": "creates" + }, + { + "id": "LUKsczhb4tA-FBj4UuVr_", + "type": "arrow", + "x": 1181.6555701966186, + "y": 761.7164081151495, + "width": 2.2019997163511107, + "height": 100.17323049763218, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 17069733, + "version": 134, + "versionNonce": 1270217381, + "isDeleted": false, + "boundElements": null, + "updated": 1642363279112, + "points": [ + [ + 0, + 0 + ], + [ + 2.2019997163511107, + 100.17323049763218 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "U-EKjQ2I8Nqp77fo0hFXS", + "focus": -0.003519884030544712, + "gap": 3.716408115149534 + }, + "endBinding": { + "elementId": "G00cPo51SxZZjScTTmW6v", + "focus": 0.04653602397004277, + "gap": 6.826769502367824 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "AnYN90VNUcVDpxC9ADTff", + "type": "arrow", + "x": 1178.9779855600796, + "y": 682.7164081151495, + "width": 1, + "height": 37, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 449404421, + "version": 24, + "versionNonce": 1236016773, + "isDeleted": false, + "boundElements": null, + "updated": 1642363291245, + "points": [ + [ + 0, + 0 + ], + [ + 1, + 37 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "ame5KpH1huZ8Ub_T8uka_", + "focus": 0.06421949253976675, + "gap": 8.716408115149534 + }, + "endBinding": { + "elementId": "U-EKjQ2I8Nqp77fo0hFXS", + "focus": -0.008772053768841522, + "gap": 3.283591884850466 + }, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "gtZquKq5CmPjBvT5zPYx_", + "type": "arrow", + "x": 2169.97798556008, + "y": 280.7164081151496, + "width": 5, + "height": 828, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "round", + "seed": 1513379403, + "version": 63, + "versionNonce": 1680068395, + "isDeleted": false, + "boundElements": null, + "updated": 1642363729657, + "points": [ + [ + 0, + 0 + ], + [ + 5, + 828 + ] + ], + "lastCommittedPoint": null, + "startBinding": { + "elementId": "pTeJ3U7XEGejOdbsJG4PK", + "focus": -0.14357046172356744, + "gap": 7 + }, + "endBinding": null, + "startArrowhead": null, + "endArrowhead": "arrow" + }, + { + "id": "pTeJ3U7XEGejOdbsJG4PK", + "type": "text", + "x": 2146.97798556008, + "y": 248.7164081151496, + "width": 40, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 951153637, + "version": 20, + "versionNonce": 1009011973, + "isDeleted": false, + "boundElements": [ + { + "id": "gtZquKq5CmPjBvT5zPYx_", + "type": "arrow" + } + ], + "updated": 1642363729657, + "text": "time", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 18, + "containerId": null, + "originalText": "time" + }, + { + "id": "rmYZa4dRgx0upN4eNZ4yT", + "type": "text", + "x": 2169.97798556008, + "y": 1110.7164081151498, + "width": 12, + "height": 25, + "angle": 0, + "strokeColor": "#000000", + "backgroundColor": "#4c6ef5", + "fillStyle": "hachure", + "strokeWidth": 1, + "strokeStyle": "solid", + "roughness": 1, + "opacity": 100, + "groupIds": [], + "strokeSharpness": "sharp", + "seed": 1448362091, + "version": 3, + "versionNonce": 241629963, + "isDeleted": false, + "boundElements": null, + "updated": 1642363731040, + "text": "t", + "fontSize": 20, + "fontFamily": 1, + "textAlign": "left", + "verticalAlign": "top", + "baseline": 18, + "containerId": null, + "originalText": "t" + } + ], + "appState": { + "gridSize": null, + "viewBackgroundColor": "#ffffff" + }, + "files": {} +} \ No newline at end of file diff --git a/rl_studio/envs/f1/env_type.py b/rl_studio/envs/f1/env_type.py index 409e54443..a98aef826 100644 --- a/rl_studio/envs/f1/env_type.py +++ b/rl_studio/envs/f1/env_type.py @@ -1,7 +1,7 @@ from enum import Enum -class TrainingType(Enum): +class EnvironmentType(Enum): qlearn_env_camera = "qlearn_camera" qlearn_env_laser = "qlearn_laser" dqn_env = "dqn" diff --git a/rl_studio/envs/f1/exceptions.py b/rl_studio/envs/f1/exceptions.py index 44d8c5fe9..ce4adf240 100644 --- a/rl_studio/envs/f1/exceptions.py +++ b/rl_studio/envs/f1/exceptions.py @@ -2,8 +2,8 @@ class CreationError(Exception): ... -class NoValidTrainingType(CreationError): - def __init__(self, training_type): - self.traning_type = training_type - self.message = f"[MEESAGE] No valid training type ({training_type}) in your settings.py file" +class NoValidEnvironmentType(CreationError): + def __init__(self, environment_type): + self.traning_type = environment_type + self.message = f"[MEESAGE] No valid training type ({environment_type}) in your settings.py file" super().__init__(self.message) diff --git a/rl_studio/envs/f1/models/__init__.py b/rl_studio/envs/f1/models/__init__.py index 1c4781584..6b88e6e77 100644 --- a/rl_studio/envs/f1/models/__init__.py +++ b/rl_studio/envs/f1/models/__init__.py @@ -1,5 +1,5 @@ -from rl_studio.envs.f1.env_type import TrainingType -from rl_studio.envs.f1.exceptions import NoValidTrainingType +from rl_studio.envs.f1.env_type import EnvironmentType +from rl_studio.envs.f1.exceptions import NoValidEnvironmentType class F1Env: @@ -16,22 +16,22 @@ def __new__(cls, **config): training_type = config.get("training_type") - if training_type == TrainingType.qlearn_env_camera.value: + if training_type == EnvironmentType.qlearn_env_camera.value: from rl_studio.envs.f1.models.f1_env_camera import F1CameraEnv return F1CameraEnv(**config) - elif training_type == TrainingType.qlearn_env_laser.value: + elif training_type == EnvironmentType.qlearn_env_laser.value: from rl_studio.envs.f1.models.f1_env_qlearn_laser import F1QlearnLaserEnv return F1QlearnLaserEnv(**config) - elif training_type == TrainingType.dqn_env.value: + elif training_type == EnvironmentType.dqn_env.value: from rl_studio.envs.f1.models.f1_env_dqn_camera import GazeboF1CameraEnvDQN return GazeboF1CameraEnvDQN(**config) - elif training_type == TrainingType.manual_env.value: + elif training_type == EnvironmentType.manual_env.value: from rl_studio.envs.f1.models.f1_env_manual_pilot import ( GazeboF1ManualCameraEnv, ) @@ -39,4 +39,4 @@ def __new__(cls, **config): return GazeboF1ManualCameraEnv(**config) else: - raise NoValidTrainingType(training_type) + raise NoValidEnvironmentType(training_type) diff --git a/rl_studio/envs/f1/models/f1_env.py b/rl_studio/envs/f1/models/f1_env.py index 4078bb7e6..9d5163ea3 100644 --- a/rl_studio/envs/f1/models/f1_env.py +++ b/rl_studio/envs/f1/models/f1_env.py @@ -10,8 +10,10 @@ class F1Env(gazebo_env.GazeboEnv): def __init__(self, **config): gazebo_env.GazeboEnv.__init__(self, config.get("launch")) - self.circuit = config.get("simple") - self.alternate_pose = config.get("algernate_pose") + self.circuit_name = config.get("circuit_name") + self.circuit_positions_set = config.get("circuit_positions_set") + self.alternate_pose = config.get("alternate_pose") + self.vel_pub = rospy.Publisher("/F1ROS/cmd_vel", Twist, queue_size=5) self.unpause = rospy.ServiceProxy("/gazebo/unpause_physics", Empty) self.pause = rospy.ServiceProxy("/gazebo/pause_physics", Empty) diff --git a/rl_studio/envs/f1/models/f1_env_camera.py b/rl_studio/envs/f1/models/f1_env_camera.py index df1612186..c6591e0f5 100644 --- a/rl_studio/envs/f1/models/f1_env_camera.py +++ b/rl_studio/envs/f1/models/f1_env_camera.py @@ -11,6 +11,7 @@ from rl_studio.agents.f1.settings import QLearnConfig from rl_studio.envs.f1.image_f1 import ImageF1 from rl_studio.envs.f1.models.f1_env import F1Env +from rl_studio.envs.gazebo_utils import set_new_pose class F1CameraEnv(F1Env): @@ -18,9 +19,9 @@ def __init__(self, **config): F1Env.__init__(self, **config) self.image = ImageF1() self.actions = config.get("actions") - self.action_space = spaces.Discrete( - len(self.actions) - ) # actions # spaces.Discrete(3) # F,L,R + self.action_space = spaces.Discrete(3) + # len(self.actions) + # ) # actions # spaces.Discrete(3) # F,L,R self.config = QLearnConfig() def render(self, mode="human"): @@ -161,7 +162,7 @@ def step(self, action) -> Tuple: def reset(self): # === POSE === if self.alternate_pose: - self.set_new_pose() + pos_number = set_new_pose(self.circuit_positions_set) else: self._gazebo_reset() diff --git a/rl_studio/envs/gazebo_utils.py b/rl_studio/envs/gazebo_utils.py new file mode 100644 index 000000000..3e4bc884d --- /dev/null +++ b/rl_studio/envs/gazebo_utils.py @@ -0,0 +1,35 @@ +import random + +import rospy +from gazebo_msgs.msg import ModelState +from gazebo_msgs.srv import SetModelState + + +def set_new_pose(circuit_positions_set): + """ + Receives the set of circuit positions (specified in the yml configuration file) + and returns the index of the selected random position. + + (pos_number, pose_x, pose_y, pose_z, or_x, or_y, or_z, or_z) + """ + position = random.choice(list(enumerate(circuit_positions_set)))[0] + print(position) + # pos_number = int(circuit_positions_set[0]) + + state = ModelState() + state.model_name = "f1_renault" + state.pose.position.x = circuit_positions_set[position][1] + state.pose.position.y = circuit_positions_set[position][2] + state.pose.position.z = circuit_positions_set[position][3] + state.pose.orientation.x = circuit_positions_set[position][4] + state.pose.orientation.y = circuit_positions_set[position][5] + state.pose.orientation.z = circuit_positions_set[position][6] + state.pose.orientation.w = circuit_positions_set[position][7] + + rospy.wait_for_service("/gazebo/set_model_state") + try: + set_state = rospy.ServiceProxy("/gazebo/set_model_state", SetModelState) + set_state(state) + except rospy.ServiceException as e: + print("Service call failed: {}".format(e)) + return position diff --git a/rl_studio/main_rlstudio.py b/rl_studio/main_rlstudio.py new file mode 100644 index 000000000..24ac2af28 --- /dev/null +++ b/rl_studio/main_rlstudio.py @@ -0,0 +1,62 @@ +import argparse +import json +import yaml + +from rl_studio.agents import TrainerFactory +from rl_studio.agents.trainer import TrainerValidator + + +def get_algorithm(config_file: dict, input_algorithm: str) -> dict: + return { + "name": input_algorithm, + "params": config_file["algorithm"][input_algorithm], + } + + +def get_environment(config_file: dict, input_env: str) -> dict: + return { + "name": input_env, + "params": config_file["environments"][input_env], + "actions": config_file["actions"]["available_actions"][input_env], + } + + +def get_agent(config_file: dict, input_agent: str) -> dict: + return { + "name": input_agent, + "params": config_file["agent"][input_agent], + } + + +def main(): + parser = argparse.ArgumentParser() + parser.add_argument("-f", "--file", type=argparse.FileType("r"), required=True, default="config.yml") + parser.add_argument("-a", "--agent", type=str, required=True) + parser.add_argument("-e", "--environment", type=str, required=True) + parser.add_argument("-n", "--algorithm", type=str, required=True) + args = parser.parse_args() + + config_file = yaml.load(args.file) + # print(f"INPUT CONFIGURATION FILE:\n{yaml.dump(config_file, indent=4)}") + + trainer_params = { + "settings": config_file["settings"], + "algorithm": get_algorithm(config_file, args.algorithm), + "environment": get_environment(config_file, args.environment), + "agent": get_agent(config_file, args.agent), + } + + # TODO: Create function to check dirs + # os.makedirs("logs", exist_ok=True) + # os.makedirs("images", exist_ok=True) + + # PARAMS + params = TrainerValidator(**trainer_params) + print("PARAMS:\n") + print(json.dumps(dict(params), indent=2)) + trainer = TrainerFactory(params) + trainer.main() + + +if __name__ == '__main__': + main() diff --git a/rl_studio/visual/ascii/images.py b/rl_studio/visual/ascii/images.py index c20b7c81f..97f7ca7d3 100644 --- a/rl_studio/visual/ascii/images.py +++ b/rl_studio/visual/ascii/images.py @@ -1,3 +1,7 @@ +""" +References: http://www.patorjk.com/software/taag/#p=display&f=Sub-Zero&t=Aliasrc%20 +""" + JDEROBOT_LOGO = """ ``..--------..`` `.-:/::--.........--:/:-.` diff --git a/rl_studio/visual/ascii/text.py b/rl_studio/visual/ascii/text.py index cb06eb439..a69312cc5 100644 --- a/rl_studio/visual/ascii/text.py +++ b/rl_studio/visual/ascii/text.py @@ -1,3 +1,7 @@ +""" +References: http://www.patorjk.com/software/taag/#p=display&f=Sub-Zero&t=Aliasrc%20 +""" + LETS_GO = """ ______ __ / ____/___ / /